From 66deae172d7d7db04cf7c80dff8acc2bf66af4f2 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 7 May 2025 14:44:14 +1200 Subject: [PATCH 001/130] mavsdk_tests: update to MAVSDK 3.0.0 --- test/mavsdk_tests/MAVSDK_VERSION | 2 +- test/mavsdk_tests/autopilot_tester.cpp | 52 ++++++++++--------- test/mavsdk_tests/autopilot_tester.h | 5 +- .../autopilot_tester_figure_eight.cpp | 7 +-- test/mavsdk_tests/autopilot_tester_rtl.cpp | 24 ++++++--- test/mavsdk_tests/configs/sitl.json | 2 +- 6 files changed, 53 insertions(+), 39 deletions(-) diff --git a/test/mavsdk_tests/MAVSDK_VERSION b/test/mavsdk_tests/MAVSDK_VERSION index 3a3cd8cc8b..4a36342fca 100644 --- a/test/mavsdk_tests/MAVSDK_VERSION +++ b/test/mavsdk_tests/MAVSDK_VERSION @@ -1 +1 @@ -1.3.1 +3.0.0 diff --git a/test/mavsdk_tests/autopilot_tester.cpp b/test/mavsdk_tests/autopilot_tester.cpp index 4344a35ae8..64aaf05614 100644 --- a/test/mavsdk_tests/autopilot_tester.cpp +++ b/test/mavsdk_tests/autopilot_tester.cpp @@ -215,9 +215,10 @@ void AutopilotTester::wait_until_altitude(float rel_altitude_m, std::chrono::sec auto prom = std::promise {}; auto fut = prom.get_future(); - _telemetry->subscribe_position([&prom, rel_altitude_m, delta, this](Telemetry::Position new_position) { + Telemetry::PositionHandle handle = _telemetry->subscribe_position([&prom, rel_altitude_m, delta, &handle, + this](Telemetry::Position new_position) { if (fabs(rel_altitude_m - new_position.relative_altitude_m) <= delta) { - _telemetry->subscribe_position(nullptr); + _telemetry->unsubscribe_position(handle); prom.set_value(); } }); @@ -629,7 +630,8 @@ void AutopilotTester::start_checking_altitude(const float max_deviation_m) std::array initial_position = get_current_position_ned(); float target_altitude = initial_position[2]; - _telemetry->subscribe_position([target_altitude, max_deviation_m, this](Telemetry::Position new_position) { + _check_altitude_handle = _telemetry->subscribe_position([target_altitude, max_deviation_m, + this](Telemetry::Position new_position) { const float current_deviation = fabs((-target_altitude) - new_position.relative_altitude_m); CHECK(current_deviation <= max_deviation_m); }); @@ -637,7 +639,7 @@ void AutopilotTester::start_checking_altitude(const float max_deviation_m) void AutopilotTester::stop_checking_altitude() { - _telemetry->subscribe_position(nullptr); + _telemetry->unsubscribe_position(_check_altitude_handle); } void AutopilotTester::check_tracks_mission_raw(float corridor_radius_m, bool reverse) @@ -744,15 +746,10 @@ void AutopilotTester::send_custom_mavlink_command(const MavlinkPassthrough::Comm _mavlink_passthrough->send_command_int(command); } -void AutopilotTester::send_custom_mavlink_message(mavlink_message_t &message) -{ - _mavlink_passthrough->send_message(message); -} - void AutopilotTester::add_mavlink_message_callback(uint16_t message_id, std::function< void(const mavlink_message_t &)> callback) { - _mavlink_passthrough->subscribe_message_async(message_id, std::move(callback)); + _mavlink_passthrough->subscribe_message(message_id, std::move(callback)); } std::array AutopilotTester::get_current_position_ned() @@ -867,11 +864,12 @@ void AutopilotTester::start_and_wait_for_mission_sequence(int sequence_number) auto prom = std::promise {}; auto fut = prom.get_future(); - _mission->subscribe_mission_progress([&prom, this, sequence_number](Mission::MissionProgress progress) { + Mission::MissionProgressHandle handle = _mission->subscribe_mission_progress( + [&prom, &handle, this, sequence_number](Mission::MissionProgress progress) { std::cout << time_str() << "Progress: " << progress.current << "/" << progress.total << std::endl; if (progress.current >= sequence_number) { - _mission->subscribe_mission_progress(nullptr); + _mission->unsubscribe_mission_progress(handle); prom.set_value(); } }); @@ -886,11 +884,12 @@ void AutopilotTester::start_and_wait_for_mission_sequence_raw(int sequence_numbe auto prom = std::promise {}; auto fut = prom.get_future(); - _mission_raw->subscribe_mission_progress([&prom, this, sequence_number](MissionRaw::MissionProgress progress) { + MissionRaw::MissionProgressHandle handle = _mission_raw->subscribe_mission_progress( + [&prom, &handle, this, sequence_number](MissionRaw::MissionProgress progress) { std::cout << time_str() << "Progress: " << progress.current << "/" << progress.total << std::endl; if (progress.current >= sequence_number) { - _mission_raw->subscribe_mission_progress(nullptr); + _mission_raw->unsubscribe_mission_progress(handle); prom.set_value(); } }); @@ -905,9 +904,10 @@ void AutopilotTester::wait_for_flight_mode(Telemetry::FlightMode flight_mode, st auto prom = std::promise {}; auto fut = prom.get_future(); - _telemetry->subscribe_flight_mode([&prom, flight_mode, this](Telemetry::FlightMode new_flight_mode) { + Telemetry::FlightModeHandle handle = _telemetry->subscribe_flight_mode( + [&prom, &handle, flight_mode, this](Telemetry::FlightMode new_flight_mode) { if (new_flight_mode == flight_mode) { - _telemetry->subscribe_flight_mode(nullptr); + _telemetry->unsubscribe_flight_mode(handle); prom.set_value(); } }); @@ -920,9 +920,10 @@ void AutopilotTester::wait_for_landed_state(Telemetry::LandedState landed_state, auto prom = std::promise {}; auto fut = prom.get_future(); - _telemetry->subscribe_landed_state([&prom, landed_state, this](Telemetry::LandedState new_landed_state) { + Telemetry::LandedStateHandle handle = _telemetry->subscribe_landed_state( + [&prom, &handle, landed_state, this](Telemetry::LandedState new_landed_state) { if (new_landed_state == landed_state) { - _telemetry->subscribe_landed_state(nullptr); + _telemetry->unsubscribe_landed_state(handle); prom.set_value(); } }); @@ -935,7 +936,8 @@ void AutopilotTester::wait_until_speed_lower_than(float speed, std::chrono::seco auto prom = std::promise {}; auto fut = prom.get_future(); - _telemetry->subscribe_position_velocity_ned([&prom, speed, this](Telemetry::PositionVelocityNed position_velocity_ned) { + Telemetry::PositionVelocityNedHandle handle = _telemetry->subscribe_position_velocity_ned( + [&prom, &handle, speed, this](Telemetry::PositionVelocityNed position_velocity_ned) { std::array current_velocity; current_velocity[0] = position_velocity_ned.velocity.north_m_s; current_velocity[1] = position_velocity_ned.velocity.east_m_s; @@ -943,7 +945,7 @@ void AutopilotTester::wait_until_speed_lower_than(float speed, std::chrono::seco const float current_speed = norm(current_velocity); if (current_speed <= speed) { - _telemetry->subscribe_position_velocity_ned(nullptr); + _telemetry->unsubscribe_position_velocity_ned(handle); prom.set_value(); } }); @@ -956,9 +958,10 @@ void AutopilotTester::wait_for_mission_finished(std::chrono::seconds timeout) auto prom = std::promise {}; auto fut = prom.get_future(); - _mission->subscribe_mission_progress([&prom, this](Mission::MissionProgress progress) { + Mission::MissionProgressHandle handle = _mission->subscribe_mission_progress( + [&prom, &handle, this](Mission::MissionProgress progress) { if (progress.current == progress.total) { - _mission->subscribe_mission_progress(nullptr); + _mission->unsubscribe_mission_progress(handle); prom.set_value(); } }); @@ -971,9 +974,10 @@ void AutopilotTester::wait_for_mission_raw_finished(std::chrono::seconds timeout auto prom = std::promise {}; auto fut = prom.get_future(); - _mission_raw->subscribe_mission_progress([&prom, this](MissionRaw::MissionProgress progress) { + MissionRaw::MissionProgressHandle handle = _mission_raw->subscribe_mission_progress( + [&prom, &handle, this](MissionRaw::MissionProgress progress) { if (progress.current == progress.total) { - _mission_raw->subscribe_mission_progress(nullptr); + _mission_raw->unsubscribe_mission_progress(handle); prom.set_value(); } }); diff --git a/test/mavsdk_tests/autopilot_tester.h b/test/mavsdk_tests/autopilot_tester.h index 802bc819a3..8fcb48b58c 100644 --- a/test/mavsdk_tests/autopilot_tester.h +++ b/test/mavsdk_tests/autopilot_tester.h @@ -149,7 +149,6 @@ public: void check_current_altitude(float target_rel_altitude_m, float max_distance_m = 1.5f); void execute_rtl_when_reaching_mission_sequence(int sequence_number); void send_custom_mavlink_command(const MavlinkPassthrough::CommandInt &command); - void send_custom_mavlink_message(mavlink_message_t &message); void add_mavlink_message_callback(uint16_t message_id, std::function< void(const mavlink_message_t &)> callback); void enable_fixedwing_mectrics(); @@ -282,7 +281,7 @@ private: } - mavsdk::Mavsdk _mavsdk{}; + mavsdk::Mavsdk _mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; std::unique_ptr _action{}; std::unique_ptr _failure{}; std::unique_ptr _info{}; @@ -296,6 +295,8 @@ private: Telemetry::GroundTruth _home{NAN, NAN, NAN}; + mavsdk::Telemetry::PositionHandle _check_altitude_handle{}; + std::atomic _should_exit {false}; std::thread _real_time_report_thread {}; }; diff --git a/test/mavsdk_tests/autopilot_tester_figure_eight.cpp b/test/mavsdk_tests/autopilot_tester_figure_eight.cpp index 402c72d3a2..2d6e8f0b85 100644 --- a/test/mavsdk_tests/autopilot_tester_figure_eight.cpp +++ b/test/mavsdk_tests/autopilot_tester_figure_eight.cpp @@ -103,7 +103,8 @@ void AutopilotTesterFigureEight::check_tracks_figure_eight(std::chrono::seconds order_to_fly = std::vector {0, 3, 2, 1, 0, 6, 5, 4, 0}; } - getTelemetry()->subscribe_position_velocity_ned([&figure_eight_point_of_interest, &prom, corridor_radius_m, + Telemetry::PositionVelocityNedHandle handle = getTelemetry()->subscribe_position_velocity_ned( + [&figure_eight_point_of_interest, &prom, &handle, corridor_radius_m, &order_to_fly, this](Telemetry::PositionVelocityNed position_velocity_ned) { static size_t index{0}; int32_t close_index{-1}; @@ -129,14 +130,14 @@ void AutopilotTesterFigureEight::check_tracks_figure_eight(std::chrono::seconds } else { // reached an out of order point if (index > 0U) { // only set to false if we already hve passed the first center point - getTelemetry()->subscribe_position_velocity_ned(nullptr); + getTelemetry()->unsubscribe_position_velocity_ned(handle); prom.set_value(false); } } } if (index + 1 == order_to_fly.size()) { - getTelemetry()->subscribe_position_velocity_ned(nullptr); + getTelemetry()->unsubscribe_position_velocity_ned(handle); prom.set_value(true); } }); diff --git a/test/mavsdk_tests/autopilot_tester_rtl.cpp b/test/mavsdk_tests/autopilot_tester_rtl.cpp index d24b59e90d..df2bd946ea 100644 --- a/test/mavsdk_tests/autopilot_tester_rtl.cpp +++ b/test/mavsdk_tests/autopilot_tester_rtl.cpp @@ -79,10 +79,12 @@ void AutopilotTesterRtl::upload_custom_mission(std::chrono::seconds timeout) if (request_int_message.mission_type == mission_type) { // send requested element. - mavlink_message_t mission_item_int_mavlink_message; - mavlink_msg_mission_item_int_encode(getMavlinkPassthrough()->get_our_sysid(), getMavlinkPassthrough()->get_our_compid(), - &mission_item_int_mavlink_message, &(_custom_mission[request_int_message.seq])); - send_custom_mavlink_message(mission_item_int_mavlink_message); + getMavlinkPassthrough()->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message; + mavlink_msg_mission_item_int_encode_chan(mavlink_address.system_id, mavlink_address.component_id, channel, + &message, &(_custom_mission[request_int_message.seq])); + return message; + }); if (request_int_message.seq + 1U == _custom_mission.size()) { add_mavlink_message_callback(MAVLINK_MSG_ID_MISSION_REQUEST_INT, nullptr); @@ -102,7 +104,12 @@ void AutopilotTesterRtl::upload_custom_mission(std::chrono::seconds timeout) mavlink_msg_mission_count_encode(getMavlinkPassthrough()->get_our_sysid(), getMavlinkPassthrough()->get_our_compid(), &mission_count_mavlink_message, &mission_count_message); - send_custom_mavlink_message(mission_count_mavlink_message); + getMavlinkPassthrough()->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message; + mavlink_msg_mission_count_encode_chan(mavlink_address.system_id, mavlink_address.component_id, channel, + &message, &mission_count_message); + return message; + }); REQUIRE(fut.wait_for(timeout) == std::future_status::ready); } @@ -222,7 +229,8 @@ void AutopilotTesterRtl::check_rtl_approaches(float acceptance_radius_m, std::ch REQUIRE(return_rtl_alt.first == Param::Result::Success); REQUIRE(descend_rtl_alt.first == Param::Result::Success); - getTelemetry()->subscribe_position_velocity_ned([&prom, acceptance_radius_m, return_rtl_alt, descend_rtl_alt, ct, + Telemetry::PositionVelocityNedHandle handle = getTelemetry()->subscribe_position_velocity_ned( + [&prom, &handle, acceptance_radius_m, return_rtl_alt, descend_rtl_alt, ct, this](Telemetry::PositionVelocityNed position_velocity_ned) { if ((-position_velocity_ned.position.down_m < return_rtl_alt.second - 3.) @@ -242,7 +250,7 @@ void AutopilotTesterRtl::check_rtl_approaches(float acceptance_radius_m, std::ch if (-position_velocity_ned.position.down_m < descend_rtl_alt.second + 3.) { // We reached the altitude - getTelemetry()->subscribe_position_velocity_ned(nullptr); + getTelemetry()->unsubscribe_position_velocity_ned(handle); prom.set_value(true); return; @@ -252,7 +260,7 @@ void AutopilotTesterRtl::check_rtl_approaches(float acceptance_radius_m, std::ch } if (!on_approach_loiter) { - getTelemetry()->subscribe_position_velocity_ned(nullptr); + getTelemetry()->unsubscribe_position_velocity_ned(handle); prom.set_value(false); } diff --git a/test/mavsdk_tests/configs/sitl.json b/test/mavsdk_tests/configs/sitl.json index e14b73689c..a281c2fe2a 100644 --- a/test/mavsdk_tests/configs/sitl.json +++ b/test/mavsdk_tests/configs/sitl.json @@ -1,7 +1,7 @@ { "mode": "sitl", "simulator": "gazebo", - "mavlink_connection": "udp://:14540", + "mavlink_connection": "udpin://0.0.0.0:14540", "tests": [ { From e19d245355725abd634635de0990dabb8ca447dc Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 7 May 2025 20:57:27 +1200 Subject: [PATCH 002/130] mavsdk_tests: remove hacks for rally points We can now just use MAVSDK to upload rally points. --- test/mavsdk_tests/autopilot_tester.h | 1 + test/mavsdk_tests/autopilot_tester_rtl.cpp | 81 +++++----------------- test/mavsdk_tests/autopilot_tester_rtl.h | 8 +-- test/mavsdk_tests/test_vtol_rtl.cpp | 14 ++-- 4 files changed, 28 insertions(+), 76 deletions(-) diff --git a/test/mavsdk_tests/autopilot_tester.h b/test/mavsdk_tests/autopilot_tester.h index 8fcb48b58c..e7f5f895b7 100644 --- a/test/mavsdk_tests/autopilot_tester.h +++ b/test/mavsdk_tests/autopilot_tester.h @@ -191,6 +191,7 @@ public: protected: mavsdk::Param *getParams() const { return _param.get();} mavsdk::Telemetry *getTelemetry() const { return _telemetry.get();} + mavsdk::MissionRaw *getMissionRaw() const { return _mission_raw.get();} mavsdk::ManualControl *getManualControl() const { return _manual_control.get();} MavlinkPassthrough *getMavlinkPassthrough() const { return _mavlink_passthrough.get();} std::shared_ptr get_system() { return _mavsdk.systems().at(0);} diff --git a/test/mavsdk_tests/autopilot_tester_rtl.cpp b/test/mavsdk_tests/autopilot_tester_rtl.cpp index df2bd946ea..200cf66a24 100644 --- a/test/mavsdk_tests/autopilot_tester_rtl.cpp +++ b/test/mavsdk_tests/autopilot_tester_rtl.cpp @@ -64,54 +64,9 @@ void AutopilotTesterRtl::set_takeoff_land_requirements(int req) CHECK(getParams()->set_param_int("MIS_TKO_LAND_REQ", req) == Param::Result::Success); } -void AutopilotTesterRtl::upload_custom_mission(std::chrono::seconds timeout) +void AutopilotTesterRtl::upload_rally_points() { - std::promise prom; - auto fut = prom.get_future(); - - uint8_t mission_type = _custom_mission[0].mission_type; - // Register callback to mission item request. - add_mavlink_message_callback(MAVLINK_MSG_ID_MISSION_REQUEST_INT, [this, mission_type, - &prom](const mavlink_message_t &message) { - - mavlink_mission_request_int_t request_int_message; - mavlink_msg_mission_request_int_decode(&message, &request_int_message); - - if (request_int_message.mission_type == mission_type) { - // send requested element. - getMavlinkPassthrough()->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { - mavlink_message_t message; - mavlink_msg_mission_item_int_encode_chan(mavlink_address.system_id, mavlink_address.component_id, channel, - &message, &(_custom_mission[request_int_message.seq])); - return message; - }); - - if (request_int_message.seq + 1U == _custom_mission.size()) { - add_mavlink_message_callback(MAVLINK_MSG_ID_MISSION_REQUEST_INT, nullptr); - prom.set_value(); - } - } - }); - - // send mission count - mavlink_mission_count_t mission_count_message; - mission_count_message.count = _custom_mission.size(); - mission_count_message.target_system = getMavlinkPassthrough()->get_target_sysid(); - mission_count_message.target_component = getMavlinkPassthrough()->get_target_compid(); - mission_count_message.mission_type = mission_type; - - mavlink_message_t mission_count_mavlink_message; - mavlink_msg_mission_count_encode(getMavlinkPassthrough()->get_our_sysid(), getMavlinkPassthrough()->get_our_compid(), - &mission_count_mavlink_message, &mission_count_message); - - getMavlinkPassthrough()->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { - mavlink_message_t message; - mavlink_msg_mission_count_encode_chan(mavlink_address.system_id, mavlink_address.component_id, channel, - &message, &mission_count_message); - return message; - }); - - REQUIRE(fut.wait_for(timeout) == std::future_status::ready); + REQUIRE(getMissionRaw()->upload_rally_points(_rally_points) == MissionRaw::Result::Success); } void AutopilotTesterRtl::add_home_to_rally_point() @@ -128,13 +83,13 @@ void AutopilotTesterRtl::add_home_with_approaches_to_rally_point() void AutopilotTesterRtl::add_local_rally_point(mavsdk::geometry::CoordinateTransformation::LocalCoordinate local_coordinate) { - _rally_points.push_back(local_coordinate); + _local_rally_points.push_back(local_coordinate); mavsdk::geometry::CoordinateTransformation ct(get_coordinate_transformation()); mavsdk::geometry::CoordinateTransformation::GlobalCoordinate pos(ct.global_from_local(local_coordinate)); // Set rally point - mavlink_mission_item_int_t tmp_mission_item; + mavsdk::MissionRaw::MissionItem tmp_mission_item; tmp_mission_item.param1 = 0.f; tmp_mission_item.param2 = 0.f; tmp_mission_item.param3 = 0.f; @@ -142,16 +97,15 @@ void AutopilotTesterRtl::add_local_rally_point(mavsdk::geometry::CoordinateTrans tmp_mission_item.x = static_cast(pos.latitude_deg * 1E7); tmp_mission_item.y = static_cast(pos.longitude_deg * 1E7); tmp_mission_item.z = 0.f; - tmp_mission_item.seq = static_cast(_custom_mission.size()); + tmp_mission_item.seq = static_cast(_rally_points.size()); tmp_mission_item.command = MAV_CMD_NAV_RALLY_POINT; - tmp_mission_item.target_system = getMavlinkPassthrough()->get_target_sysid(); - tmp_mission_item.target_component = getMavlinkPassthrough()->get_target_compid(); tmp_mission_item.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; - tmp_mission_item.current = 0; + // FIXME: this is currently required with MAVSDK even though it doesn't make much sense for rally points + tmp_mission_item.current = _rally_points.empty() ? 1 : 0; tmp_mission_item.autocontinue = 0; tmp_mission_item.mission_type = MAV_MISSION_TYPE_RALLY; - _custom_mission.push_back(tmp_mission_item); + _rally_points.push_back(tmp_mission_item); } void AutopilotTesterRtl::add_local_rally_with_approaches_point( @@ -171,7 +125,7 @@ void AutopilotTesterRtl::add_approaches_to_point(mavsdk::geometry::CoordinateTra mavsdk::geometry::CoordinateTransformation::LocalCoordinate tmp_coordinate{local_coordinate}; tmp_coordinate.north_m += 200.; mavsdk::geometry::CoordinateTransformation::GlobalCoordinate pos(ct.global_from_local(tmp_coordinate)); - mavlink_mission_item_int_t tmp_mission_item; + mavsdk::MissionRaw::MissionItem tmp_mission_item; tmp_mission_item.param1 = 0.f; tmp_mission_item.param2 = 80.f; tmp_mission_item.param3 = 0.f; @@ -179,16 +133,15 @@ void AutopilotTesterRtl::add_approaches_to_point(mavsdk::geometry::CoordinateTra tmp_mission_item.x = static_cast(pos.latitude_deg * 1E7); tmp_mission_item.y = static_cast(pos.longitude_deg * 1E7); tmp_mission_item.z = 15.f; - tmp_mission_item.seq = static_cast(_custom_mission.size()); + tmp_mission_item.seq = static_cast(_rally_points.size()); tmp_mission_item.command = MAV_CMD_NAV_LOITER_TO_ALT; - tmp_mission_item.target_system = getMavlinkPassthrough()->get_target_sysid(); - tmp_mission_item.target_component = getMavlinkPassthrough()->get_target_compid(); tmp_mission_item.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; - tmp_mission_item.current = 0; + // FIXME: this is currently required with MAVSDK even though it doesn't make much sense for rally points + tmp_mission_item.current = _rally_points.empty() ? 1 : 0; tmp_mission_item.autocontinue = 0; tmp_mission_item.mission_type = MAV_MISSION_TYPE_RALLY; - _custom_mission.push_back(tmp_mission_item); + _rally_points.push_back(tmp_mission_item); // Set east loiter to alt tmp_coordinate = local_coordinate; @@ -196,9 +149,9 @@ void AutopilotTesterRtl::add_approaches_to_point(mavsdk::geometry::CoordinateTra pos = ct.global_from_local(tmp_coordinate); tmp_mission_item.x = static_cast(pos.latitude_deg * 1E7); tmp_mission_item.y = static_cast(pos.longitude_deg * 1E7); - tmp_mission_item.seq = static_cast(_custom_mission.size()); + tmp_mission_item.seq = static_cast(_rally_points.size()); - _custom_mission.push_back(tmp_mission_item); + _rally_points.push_back(tmp_mission_item); } void AutopilotTesterRtl::check_rally_point_within(float acceptance_radius_m) @@ -209,7 +162,7 @@ void AutopilotTesterRtl::check_rally_point_within(float acceptance_radius_m) mavsdk::geometry::CoordinateTransformation::GlobalCoordinate pos; bool within_rally_point{false}; - for (const auto &rally_point : _rally_points) { + for (const auto &rally_point : _local_rally_points) { pos = ct.global_from_local(rally_point); land_coord.latitude_deg = pos.latitude_deg; land_coord.longitude_deg = pos.longitude_deg; @@ -238,7 +191,7 @@ void AutopilotTesterRtl::check_rtl_approaches(float acceptance_radius_m, std::ch // We started to loiter down so we should be on the approach loiter bool on_approach_loiter(false); - for (const auto mission_item : _custom_mission) { + for (const auto mission_item : _rally_points) { if (mission_item.command == MAV_CMD_NAV_LOITER_TO_ALT) { mavsdk::geometry::CoordinateTransformation::LocalCoordinate pos(ct.local_from_global({static_cast(mission_item.x) / 1E7, static_cast(mission_item.y) / 1E7})); double rel_distance_to_center = sqrt(sq(position_velocity_ned.position.north_m - pos.north_m) + sq( diff --git a/test/mavsdk_tests/autopilot_tester_rtl.h b/test/mavsdk_tests/autopilot_tester_rtl.h index eaa3c5fd9d..8efbe7ecc4 100644 --- a/test/mavsdk_tests/autopilot_tester_rtl.h +++ b/test/mavsdk_tests/autopilot_tester_rtl.h @@ -59,15 +59,13 @@ public: void connect(const std::string uri); void check_rally_point_within(float acceptance_radius_m); void check_rtl_approaches(float acceptance_radius_m, std::chrono::seconds timeout); - /* NOTE mavsdk mission upload should be used when possible. Only use this when uploading a mission which is not yet suppported by mavsdk. - * Used here to to test the new way of uploading approaches for rally points. */ - void upload_custom_mission(std::chrono::seconds timeout); + void upload_rally_points(); private: void add_approaches_to_point(mavsdk::geometry::CoordinateTransformation::LocalCoordinate local_coordinate); std::unique_ptr _failure{}; - std::vector _custom_mission{}; - std::vector _rally_points{}; + std::vector _rally_points{}; + std::vector _local_rally_points{}; }; diff --git a/test/mavsdk_tests/test_vtol_rtl.cpp b/test/mavsdk_tests/test_vtol_rtl.cpp index c98a3cd3ef..75e28d3820 100644 --- a/test/mavsdk_tests/test_vtol_rtl.cpp +++ b/test/mavsdk_tests/test_vtol_rtl.cpp @@ -105,7 +105,7 @@ TEST_CASE("RTL direct home without approaches", "[vtol]") tester.set_rtl_appr_force(0); // reupload rally points with approaches tester.add_home_to_rally_point(); - tester.upload_custom_mission(std::chrono::seconds(10)); + tester.upload_rally_points(); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(4); tester.wait_until_disarmed(std::chrono::seconds(150)); @@ -124,7 +124,7 @@ TEST_CASE("RTL direct home without approaches forced", "[vtol]") tester.set_rtl_appr_force(1); // reupload rally points with approaches tester.add_home_to_rally_point(); - tester.upload_custom_mission(std::chrono::seconds(10)); + tester.upload_rally_points(); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(4); tester.wait_until_disarmed(std::chrono::seconds(150)); @@ -142,7 +142,7 @@ TEST_CASE("RTL direct home with approaches", "[vtol]") tester.set_rtl_type(0); // reupload rally points with approaches tester.add_home_with_approaches_to_rally_point(); - tester.upload_custom_mission(std::chrono::seconds(10)); + tester.upload_rally_points(); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(4); tester.check_rtl_approaches(5., std::chrono::seconds(60)); @@ -161,7 +161,7 @@ TEST_CASE("RTL direct home not as rally point", "[vtol]") tester.set_rtl_type(1); // reupload rally points with approaches tester.add_home_with_approaches_to_rally_point(); - tester.upload_custom_mission(std::chrono::seconds(10)); + tester.upload_rally_points(); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(2); tester.wait_until_disarmed(std::chrono::seconds(150)); @@ -180,7 +180,7 @@ TEST_CASE("RTL direct rally without approaches", "[vtol]") tester.set_rtl_appr_force(0); // reupload rally points with approaches tester.add_local_rally_point({100., -200.}); - tester.upload_custom_mission(std::chrono::seconds(10)); + tester.upload_rally_points(); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(3); tester.wait_until_disarmed(std::chrono::seconds(150)); @@ -200,7 +200,7 @@ TEST_CASE("RTL direct rally without approaches forced", "[vtol]") tester.set_rtl_appr_force(1); // reupload rally points with approaches tester.add_local_rally_point({100., -2000.}); - tester.upload_custom_mission(std::chrono::seconds(10)); + tester.upload_rally_points(); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(3); tester.wait_until_disarmed(std::chrono::seconds(150)); @@ -219,7 +219,7 @@ TEST_CASE("RTL direct rally with approaches", "[vtol]") tester.set_rtl_appr_force(0); // reupload rally points with approaches tester.add_local_rally_with_approaches_point({100., -200.}); - tester.upload_custom_mission(std::chrono::seconds(10)); + tester.upload_rally_points(); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(3); tester.check_rtl_approaches(5., std::chrono::seconds(60)); From 56eb9bcc18a2df3d078a5cfd4be6fa8fa3b4dccd Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 7 May 2025 20:58:12 +1200 Subject: [PATCH 003/130] mavsdk_tests: workaround race condition PX4 needs a bit of time to process an uploaded mission before it is ready to accept the mission mode. Therefore, we need to wait a bit. Alternatively, we could wait on the mission progress arriving properly, but this sleep is simple enough for now. --- test/mavsdk_tests/autopilot_tester.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/test/mavsdk_tests/autopilot_tester.cpp b/test/mavsdk_tests/autopilot_tester.cpp index 64aaf05614..fc7efa3477 100644 --- a/test/mavsdk_tests/autopilot_tester.cpp +++ b/test/mavsdk_tests/autopilot_tester.cpp @@ -245,6 +245,8 @@ void AutopilotTester::prepare_square_mission(MissionOptions mission_options) _mission->set_return_to_launch_after_mission(mission_options.rtl_at_end); REQUIRE(_mission->upload_mission(mission_plan) == Mission::Result::Success); + // PX4 needs time to realize that it now has a mission available, so we need to wait a bit here. + sleep_for(std::chrono::seconds(1)); } void AutopilotTester::prepare_straight_mission(MissionOptions mission_options) @@ -261,6 +263,8 @@ void AutopilotTester::prepare_straight_mission(MissionOptions mission_options) _mission->set_return_to_launch_after_mission(mission_options.rtl_at_end); REQUIRE(_mission->upload_mission(mission_plan) == Mission::Result::Success); + // PX4 needs time to realize that it now has a mission available, so we need to wait a bit here. + sleep_for(std::chrono::seconds(1)); } void AutopilotTester::execute_mission() @@ -390,6 +394,8 @@ void AutopilotTester::load_qgc_mission_raw_and_move_here(const std::string &plan move_mission_raw_here(import_result.second.mission_items); REQUIRE(_mission_raw->upload_mission(import_result.second.mission_items) == MissionRaw::Result::Success); + // PX4 needs time to realize that it now has a mission available, so we need to wait a bit here. + sleep_for(std::chrono::seconds(1)); } void AutopilotTester::execute_mission_raw() From 1f65cc46b96a21ffc2d18589db75b1f8d30856ee Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 16 May 2025 13:23:23 +1200 Subject: [PATCH 004/130] mavsdk_tests: bump MAVSDK to v3.3.4 --- test/mavsdk_tests/MAVSDK_VERSION | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/mavsdk_tests/MAVSDK_VERSION b/test/mavsdk_tests/MAVSDK_VERSION index 4a36342fca..a0891f563f 100644 --- a/test/mavsdk_tests/MAVSDK_VERSION +++ b/test/mavsdk_tests/MAVSDK_VERSION @@ -1 +1 @@ -3.0.0 +3.3.4 From d4be5d3ff0e7122a2bd4a069631181e08550c7b5 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 16 May 2025 13:24:12 +1200 Subject: [PATCH 005/130] mavsdk_tests: add events to log --- test/mavsdk_tests/autopilot_tester.cpp | 15 ++++++++++++++- test/mavsdk_tests/autopilot_tester.h | 4 ++++ 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/test/mavsdk_tests/autopilot_tester.cpp b/test/mavsdk_tests/autopilot_tester.cpp index fc7efa3477..4e6aea0952 100644 --- a/test/mavsdk_tests/autopilot_tester.cpp +++ b/test/mavsdk_tests/autopilot_tester.cpp @@ -52,6 +52,7 @@ AutopilotTester::AutopilotTester() : AutopilotTester::~AutopilotTester() { + _events->unsubscribe_events(_events_handle); _should_exit = true; _real_time_report_thread.join(); } @@ -76,14 +77,26 @@ void AutopilotTester::connect(const std::string uri) _offboard.reset(new Offboard(system)); _param.reset(new Param(system)); _telemetry.reset(new Telemetry(system)); + _events.reset(new Events(system)); _mavlink_passthrough.reset(new MavlinkPassthrough(system)); + + _events_handle = _events->subscribe_events([](const Events::Event & event) { + std::cout << "[" << event.log_level << "] " << event.message << std::endl; + + if (!event.description.empty()) { + std::cout << " Description: " << event.description << std::endl; + } + + std::cout << " Event name: " << event.event_namespace << "/" << event.event_name + << std::endl; + }); } void AutopilotTester::wait_until_ready() { std::cout << time_str() << "Waiting for system to be ready (system health ok & able to arm)" << std::endl; - // Wiat until the system is healthy + // Wait until the system is healthy CHECK(poll_condition_with_timeout( [this]() { return _telemetry->health_all_ok(); }, std::chrono::seconds(30))); diff --git a/test/mavsdk_tests/autopilot_tester.h b/test/mavsdk_tests/autopilot_tester.h index e7f5f895b7..b0ac078d5d 100644 --- a/test/mavsdk_tests/autopilot_tester.h +++ b/test/mavsdk_tests/autopilot_tester.h @@ -45,6 +45,7 @@ #include #include #include +#include #include "catch2/catch.hpp" #include #include @@ -293,6 +294,7 @@ private: std::unique_ptr _offboard{}; std::unique_ptr _param{}; std::unique_ptr _telemetry{}; + std::unique_ptr _events{}; Telemetry::GroundTruth _home{NAN, NAN, NAN}; @@ -300,4 +302,6 @@ private: std::atomic _should_exit {false}; std::thread _real_time_report_thread {}; + + mavsdk::Events::EventsHandle _events_handle{}; }; From 4126dde11f4892ac052c1287dbbfee922452e5e8 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 16 May 2025 16:38:39 +1200 Subject: [PATCH 006/130] mavsdk_tests: bump to v3.4.0 This should fix some of the lockups and segfaults we see. --- test/mavsdk_tests/MAVSDK_VERSION | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/mavsdk_tests/MAVSDK_VERSION b/test/mavsdk_tests/MAVSDK_VERSION index a0891f563f..18091983f5 100644 --- a/test/mavsdk_tests/MAVSDK_VERSION +++ b/test/mavsdk_tests/MAVSDK_VERSION @@ -1 +1 @@ -3.3.4 +3.4.0 From 77894b7c83844877e02f6afa1a581b3106864e6a Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Fri, 16 May 2025 09:54:06 +0200 Subject: [PATCH 007/130] ci/boards: add itcm checker, update ITCM mapping of v6xrt and tropic-community --- .github/workflows/itcm_check.yml | 61 ++++++ Tools/itcm_check.py | 185 ++++++++++++++++++ Tools/setup/optional-requirements.txt | 1 + .../scripts/itcm_functions_includes.ld | 93 +++------ .../scripts/itcm_static_functions.ld | 9 +- .../scripts/itcm_functions_includes.ld | 68 +++---- 6 files changed, 295 insertions(+), 122 deletions(-) create mode 100644 .github/workflows/itcm_check.yml create mode 100644 Tools/itcm_check.py diff --git a/.github/workflows/itcm_check.yml b/.github/workflows/itcm_check.yml new file mode 100644 index 0000000000..94ebab8780 --- /dev/null +++ b/.github/workflows/itcm_check.yml @@ -0,0 +1,61 @@ +name: ITCM check + +permissions: + contents: read + +on: + push: + branches: + - 'main' + paths-ignore: + - 'docs/**' + - '.github/**' + pull_request: + branches: + - '*' + paths-ignore: + - 'docs/**' + - '.github/**' + +jobs: + check_itcm: + name: Checking ${{ matrix.target }} + runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + container: + image: px4io/px4-dev:v1.16.0-ondemand + strategy: + fail-fast: false + matrix: + include: + - target: px4_fmu-v5x + scripts: > + boards/px4/fmu-v5x/nuttx-config/scripts/itcm_gen_functions.ld + boards/px4/fmu-v5x/nuttx-config/scripts/itcm_static_functions.ld + - target: px4_fmu-v6xrt + scripts: > + boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld + boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld + - target: nxp_tropic-community + scripts: > + boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld + boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + submodules: recursive + + - name: Git ownership workaround + run: git config --system --add safe.directory '*' + + - name: Build Target + run: make ${{ matrix.target }} + + - name: Copy built ELF + run: cp ./build/**/*.elf ./built.elf + + - name: Install itcm-check dependencies + run: pip3 install -r Tools/setup/optional-requirements.txt --break-system-packages + + - name: Execute the itcm-check + run: python3 Tools/itcm_check.py --elf-file built.elf --script-files ${{ matrix.scripts }} diff --git a/Tools/itcm_check.py b/Tools/itcm_check.py new file mode 100644 index 0000000000..ac1ffa63b7 --- /dev/null +++ b/Tools/itcm_check.py @@ -0,0 +1,185 @@ +#! /usr/bin/env python3 + +""" +Checks if the functions that should be mapped to ITCM are contained in the built ELF file. + +This helps against linker scripts that "rot" as the linker does not warn in case of a function +not existing. Thus, it is possible to forget to update the linker script after a code update. + +The tool uses the DWARF debug info and the ELF symbol table section to identify which functions +exist in the built ELF file. + +It is expected that the linker scripts that are analyzed by the tool are linker script include +files that only contain the name of the sections (functions) that should be mapped to ITCM in +the following format: +``` +*(.text.arm_ack_irq) +*(.text.arm_doirq) +*(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah) +*(.text._ZN3Ekf20controlGravityFusionERKN9estimator9imuSampleE) +[...] +``` + +A specific entry in the linker script file can be ignored by adding a comment, as shown in the following example: +``` +*(.text.arm_ack_irq) /* itcm-check-ignore */ +``` +""" + +import argparse +import re +from elftools.elf.elffile import ELFFile +from elftools.elf.sections import SymbolTableSection +from elftools.dwarf.die import DIE +from pathlib import Path +from typing import List, Set + + +def die_get_funcs_rec(die: DIE, ret: Set[str]): + """ + Recursively gets the mangled and demangled name of all functions in the given `die`. + + :param die: DIE to be processed. Is gathered recursively after passing a top DIE. + :param ret: Output set where all function names are added to. + """ + if die.tag in ("DW_TAG_subprogram", "DW_TAG_inlined_subroutine"): + link_name_att = die.attributes.get("DW_AT_linkage_name") + name_att = die.attributes.get("DW_AT_name") + if link_name_att: + ret.add(link_name_att.value.decode("utf-8")) + if name_att: + ret.add(name_att.value.decode("utf-8")) + + # Recurse into the DIE children + for child in die.iter_children(): + die_get_funcs_rec(child, ret) + + +def get_elf_symbols_from_debug(elf_path: Path) -> Set[str]: + """ + Gets all functions contained in the built ELF file using the DWARF debug info. + + :param elf_path: Path to the ELF file. + + :return: The names of the contained functions. + """ + ret = set() + with open(elf_path, 'rb') as f: + elf = ELFFile(f) + if not elf.has_dwarf_info(): + print("ELF does not have debug info. Compile with debug info.") + exit(1) + dwarf_info = elf.get_dwarf_info() + for CU in dwarf_info.iter_CUs(): + top_die = CU.get_top_DIE() + die_get_funcs_rec(top_die, ret) + + return ret + + +def get_elf_symbols_from_sections(elf_path: Path) -> Set[str]: + """ + Gets all functions contained in the built ELF file using the symbol table section. + + :param elf_path: Path to the ELF file. + + :return: The names of the contained functions. + """ + ret = set() + with open(elf_path, 'rb') as f: + elf = ELFFile(f) + for section in elf.iter_sections(): + if isinstance(section, SymbolTableSection): + for sym in section.iter_symbols(): + ret.add(sym.name) + return ret + + +def is_section_supported(section: str) -> bool: + """ + Returns whether this type of section can be checked. + + :param section: Name of the section that should be checked for support. + + :return: Whether the type of section is supported. + """ + not_supported_sections = [".isra", ".part", ".constprop"] + return not any(not_supported in section for not_supported in not_supported_sections) + + +def get_input_sections(script_path: Path) -> List[str]: + """ + Gets all sections (named after the functions) that should be mapped to ITCM according + to the linker script. + + :param script_path: Path of the linker script. + + :return: The names of the sections + """ + ret = [] + section_pattern = re.compile(r"^\*\(\.([a-zA-Z0-9_\.]+)\)$") + ignored_marker = "itcm-check-ignore" + with open(script_path, 'r') as f: + for line in f: + match = section_pattern.match(line) + if match and ignored_marker not in line: + section_name = match.group(1).replace("text.", "") + if is_section_supported(section_name): + ret.append(section_name) + return ret + + +def check_itcm(elf_path: Path, script_paths: List[Path]): + """ + Checks if all the functions that should be mapped to ITCM are contained in the built ELF file. + + :param elf_path: Path of the ELF file. + :param script_paths: Path of all linker scripts that should be checked. + """ + elf_symbols_from_debug = get_elf_symbols_from_debug(elf_path) + elf_symbols_from_sections = get_elf_symbols_from_sections(elf_path) + elf_symbols = elf_symbols_from_debug.union(elf_symbols_from_sections) + input_sections = [] + for script_path in script_paths: + script_input_sections = get_input_sections(script_path) + if script_input_sections: + input_sections.extend(script_input_sections) + else: + print(f"No input sections found in {script_path}, please check if the path is correct.") + + check_passed = True + for input_section in input_sections: + if input_section not in elf_symbols: + check_passed = False + print(f"Section: {input_section} not found in the ELF file!") + + if check_passed: + print("ITCM check passed!") + exit(0) + else: + print("ITCM check failed!") + exit(1) + + +def main(): + parser = argparse.ArgumentParser(description="Checks if functions marked for ITCM mapping exist in the ELF file.") + parser.add_argument( + "--elf-file", + help="Path of the compiled ELF file", + type=Path, + required=True + ) + parser.add_argument( + "--script-files", + help="Paths of the linker script files", + nargs="+", + type=Path, + required=True + ) + + args = parser.parse_args() + check_itcm(args.elf_file, args.script_files) + + +if __name__ == '__main__': + main() diff --git a/Tools/setup/optional-requirements.txt b/Tools/setup/optional-requirements.txt index 844ad80bb5..57c243a237 100644 --- a/Tools/setup/optional-requirements.txt +++ b/Tools/setup/optional-requirements.txt @@ -1 +1,2 @@ +pyelftools>=0.32,<1 symforce>=0.9.0 diff --git a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld index 60a76f97e1..0e6701aae2 100644 --- a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld @@ -2,7 +2,7 @@ *(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) *(.text._ZN13MavlinkStream6updateERKy) *(.text._ZN7Mavlink16update_rate_multEv) -*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) +*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) /* itcm-check-ignore */ *(.text._ZN13MavlinkStream12get_size_avgEv) *(.text._ZN16ControlAllocator3RunEv) *(.text._ZN22MulticopterRateControl3RunEv.part.0) @@ -57,7 +57,6 @@ *(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE) *(.text._ZN4EKF220PublishLocalPositionERKy) *(.text._mav_finalize_message_chan_send) -*(.text._ZN3Ekf19fixCovarianceErrorsEb) *(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb) *(.text._ZN6events12SendProtocol6updateERKy) *(.text._ZN6device3SPI8transferEPhS1_j) @@ -68,7 +67,7 @@ *(.text.nx_poll) *(.text._ZN15MavlinkReceiver3runEv) *(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh) -*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEES8_S8_S8_) +*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_) *(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE) *(.text._ZN3px46logger6Logger3runEv) *(.text._ZN4uORB20SubscriptionInterval7updatedEv) @@ -99,7 +98,6 @@ *(.text.file_vioctl) *(.text._ZN7sensors18VotedSensorsUpdate11sensorsPollER17sensor_combined_s) *(.text.nxsig_nanosleep) -*(.text.imxrt_lpspi1select) *(.text.sem_wait) *(.text.perf_count_interval.part.0) *(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason) @@ -122,7 +120,6 @@ *(.text._ZN22MulticopterRateControl28updateActuatorControlsStatusERK25vehicle_torque_setpoint_sf) *(.text._ZN11RateControl6updateERKN6matrix7Vector3IfEES4_S4_fb) *(.text._ZN39ControlAllocationSequentialDesaturation19desaturateActuatorsERN6matrix6VectorIfLj16EEERKS2_b) -*(.text._ZN22MavlinkStreamCollision4sendEv) *(.text.imxrt_lpi2c_transfer) *(.text.uart_putxmitchar) *(.text.clock_nanosleep) @@ -154,7 +151,6 @@ *(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE) *(.text._ZN9Commander13dataLinkCheckEv) *(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex) -*(.text._ZNK3Ekf26get_innovation_test_statusERtRfS1_S1_S1_S1_S1_S1_) *(.text._ZN12PX4Gyroscope9set_scaleEf) *(.text._ZN12FailsafeBase6updateERKyRKNS_5StateEbbRK16failsafe_flags_s) *(.text._ZN18MavlinkStreamDebug4sendEv) @@ -167,11 +163,10 @@ *(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv) *(.text.imxrt_dmach_start) *(.text._ZN3ADC19update_system_powerEy) -*(.text._ZNK3Ekf19get_ekf_soln_statusEPt) +*(.text._ZNK3Ekf19get_ekf_soln_statusEv) *(.text._ZN3px46logger15watchdog_updateERNS0_15watchdog_data_tEb) *(.text.imxrt_gpio_read) *(.text._ZN32MavlinkStreamNavControllerOutput4sendEv) -*(.text._ZN15ArchPX4IOSerial13_bus_exchangeEP8IOPacket) *(.text._ZN39MavlinkStreamGimbalDeviceAttitudeStatus4sendEv) *(.text._ZNK10ConstLayer3getEt) *(.text.__aeabi_uldivmod) @@ -194,11 +189,9 @@ *(.text._ZN22MavlinkStreamGPSStatus4sendEv) *(.text._ZN4EKF220UpdateAirspeedSampleER17ekf2_timestamps_s) *(.text._ZN23MavlinkStreamStatustext4sendEv) -*(.text._ZN3Ekf15constrainStatesEv) -*(.text._ZN12PX4IO_serial4readEjPvj) *(.text.uart_poll) *(.text._ZN24MavlinkParametersManager4sendEv) -*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_s) +*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_sf) *(.text.file_poll) *(.text.hrt_elapsed_time) *(.text._ZN7Mavlink11send_finishEv) @@ -232,8 +225,7 @@ *(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE) *(.text.imxrt_queuedtd) *(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv) -*(.text._ZN3Ekf16fuseVelPosHeightEffi) -*(.text._ZN3Ekf23controlBaroHeightFusionEv) +*(.text._ZN3Ekf23controlBaroHeightFusionERKN9estimator9imuSampleE) *(.text._ZN16PX4Accelerometer9set_scaleEf) *(.text._ZN11ControlMath11constrainXYERKN6matrix7Vector2IfEES4_RKf) *(.text._ZN22MavlinkStreamEfiStatus4sendEv) @@ -243,13 +235,11 @@ *(.text._ZN15PositionControl11_inputValidEv) *(.text._ZN7sensors14VehicleAirData3RunEv) *(.text.perf_count) -*(.text._ZN3Ekf16controlMagFusionEv) +*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE) *(.text.pthread_sem_give) *(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb) -*(.text._ZN30MavlinkStreamUTMGlobalPosition4sendEv) *(.text._ZN4uORB20SubscriptionInterval4copyEPv) *(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv) -*(.text._ZN17ObstacleAvoidanceC1EP12ModuleParams) *(.text.imxrt_epcomplete.constprop.0) *(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_) *(.text._ZN9Commander30handleModeIntentionAndFailsafeEv) @@ -260,7 +250,6 @@ *(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv) *(.text.pthread_mutex_add) *(.text._ZN12HomePosition6updateEbb) -*(.text._ZN5PX4IO3RunEv) *(.text.poll_fdsetup) *(.text._ZN15PositionControl20_accelerationControlEv) *(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE) @@ -280,7 +269,7 @@ *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_) *(.text.udp_pollsetup) *(.text._ZL14timer_callbackPv) -*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj23EEEf) +*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf) *(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi) *(.text.nxsem_wait_irq) *(.text._ZN20MavlinkCommandSender4lockEv) @@ -299,7 +288,7 @@ *(.text._ZN25MavlinkStreamHomePosition4sendEv) *(.text._ZN24MavlinkParametersManager8send_oneEv) *(.text._ZN15OutputPredictor29applyCorrectionToOutputBufferERKN6matrix7Vector3IfEES4_) -*(.text._ZN21HealthAndArmingChecks6updateEb) +*(.text._ZN21HealthAndArmingChecks6updateEbb) *(.text._ZThn24_N22MulticopterRateControl3RunEv) *(.text._ZN26MavlinkStreamManualControl4sendEv) *(.text._ZN27MavlinkStreamOpticalFlowRad4sendEv) @@ -307,14 +296,11 @@ *(.text._ZN4uORB7Manager11orb_publishEPK12orb_metadataPvPKv) *(.text._ZN24MavlinkParametersManager18send_untransmittedEv) *(.text._ZN10MavlinkFTP4sendEv) -*(.text._ZN15ArchPX4IOSerial13_do_interruptEv) -*(.text._ZN3Ekf27controlExternalVisionFusionEv) +*(.text._ZN3Ekf27controlExternalVisionFusionERKN9estimator9imuSampleE) *(.text.clock_gettime) *(.text._ZN3ADC17update_adc_reportEy) -*(.text._ZN3sym25ComputeYaw312InnovVarAndHIfEEvRKN6matrix6MatrixIT_Lj24ELj1EEERKNS2_IS3_Lj23ELj23EEES3_S3_PS3_PNS2_IS3_Lj23ELj1EEE) -*(.text._ZN3Ekf19runTerrainEstimatorERKN9estimator9imuSampleE) *(.text._ZN32MavlinkStreamGimbalManagerStatus4sendEv) -*(.text._ZN9LockGuardD1Ev) +*(.text._ZN9LockGuardD1Ev) /* itcm-check-ignore */ *(.text._ZN4EKF213PublishStatesERKy) *(.text._ZN3ADC3RunEv) *(.text._ZN6BMP38815compensate_dataEhPK16bmp3_uncomp_dataP9bmp3_data) @@ -336,13 +322,11 @@ *(.text._ZThn16_N7sensors22VehicleAngularVelocity3RunEv) *(.text._ZN29MavlinkStreamObstacleDistance4sendEv) *(.text._ZN24MavlinkStreamOrbitStatus4sendEv) -*(.text._ZN16PreFlightChecker26preFlightCheckHeightFailedERK23estimator_innovations_sf) *(.text._ZN9Navigator3runEv) *(.text._ZN24MavlinkParametersManager11send_paramsEv) *(.text._ZN17MavlinkLogHandler4sendEv) *(.text._ZN7control10SuperBlock5setDtEf) *(.text._ZN29MavlinkStreamMountOrientation8get_sizeEv) -*(.text._ZN5PX4IO13io_get_statusEv) *(.text._ZN26MulticopterAttitudeControl3RunEv) *(.text._ZThn16_N31ActuatorEffectivenessMultirotor22getEffectivenessMatrixERN21ActuatorEffectiveness13ConfigurationE25EffectivenessUpdateReason) *(.text._ZN4EKF218PublishStatusFlagsERKy) @@ -350,13 +334,12 @@ *(.text._ZN15FailureDetector6updateERK16vehicle_status_sRK22vehicle_control_mode_s) *(.text._ZN7Mavlink10send_startEi) *(.text.imxrt_lpspi_setbits) -*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEf) +*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEff) *(.text._ZN4EKF222UpdateAccelCalibrationERKy) *(.text._ZN7sensors19VehicleMagnetometer3RunEv) *(.text._ZN29MavlinkStreamMountOrientation4sendEv) *(.text._ZN13land_detector12LandDetector19UpdateVehicleAtRestEv) *(.text._ZN10FlightTask29_evaluateVehicleLocalPositionEv) -*(.text.board_autoled_off) *(.text.__aeabi_f2lz) *(.text._ZN32MavlinkStreamCameraImageCaptured4sendEv) *(.text._ZN21MavlinkStreamOdometry8get_sizeEv) @@ -365,24 +348,19 @@ *(.text.poll) *(.text._ZN14FlightTaskAutoD1Ev) *(.text._ZN4uORB10DeviceNode22get_initial_generationEv) -*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator9gpsSampleE) +*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator10gnssSampleE) *(.text._ZN3Ekf40updateOnGroundMotionForOpticalFlowChecksEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1Ev) *(.text._ZN14ZeroGyroUpdate6updateER3EkfRKN9estimator9imuSampleE) *(.text._ZN30MavlinkStreamOpenDroneIdSystem4sendEv) *(.text._ZN22MavlinkStreamScaledIMU4sendEv) -*(.text._ZN46MavlinkStreamTrajectoryRepresentationWaypoints4sendEv) *(.text.imxrt_ioctl) -*(.text._ZN3Ekf25checkMagBiasObservabilityEv) *(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv) -*(.text._ZN16PreFlightChecker6updateEfRK23estimator_innovations_s) *(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0) *(.text._ZN19StickAccelerationXYC1EP12ModuleParams) *(.text.imxrt_epsubmit) *(.text._ZN15PositionControl6updateEf) -*(.text._ZN3Ekf29checkVerticalAccelerationBiasERKN9estimator9imuSampleE) *(.text._ZN23MavlinkStreamScaledIMU24sendEv) -*(.text._ZN5PX4IO10io_reg_getEhhPtj) *(.text.imxrt_dma_send) *(.text._ZN20MavlinkStreamWindCov4sendEv) *(.text._ZN7sensors18VotedSensorsUpdate13checkFailoverERNS0_10SensorDataEPKcN6events3px45enums13sensor_type_tE) @@ -405,7 +383,7 @@ *(.text._ZN9Commander11updateTunesEv) *(.text._ZN4EKF215UpdateMagSampleER17ekf2_timestamps_s) *(.text._ZN18DataValidatorGroup3putEjyPKfmh) -*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_) +*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_S0_) *(.text._ZN12FailsafeBase13checkFailsafeEibbRKNS_13ActionOptionsE) *(.text._ZN17FlightTaskDescendD1Ev) *(.text._ZN30MavlinkStreamOpenDroneIdSystem8get_sizeEv) @@ -413,7 +391,6 @@ *(.text._ZN24FlightTaskManualAltitudeD1Ev) *(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb) *(.text.uart_pollnotify) -*(.text._ZN3Ekf11predictHaglERKN9estimator9imuSampleE) *(.text._ZN4EKF215PublishBaroBiasERKy) *(.text._ZN4EKF221UpdateGyroCalibrationERKy) *(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) @@ -444,7 +421,7 @@ *(.text.clock_systime_timespec) *(.text._ZN4uORB10DeviceNode26remove_internal_subscriberEv) *(.text._ZThn16_N4EKF23RunEv) -*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj23EEE) +*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj24EEE) *(.text._ZN12ActuatorTest6updateEif) *(.text._ZN17VelocitySmoothingC1Efff) *(.text._ZN13AnalogBattery19get_voltage_channelEv) @@ -459,11 +436,10 @@ *(.text._ZN14FlightTaskAuto17_evaluateTripletsEv) *(.text._ZN11calibration9Gyroscope23SensorCorrectionsUpdateEb) *(.text._ZN25MavlinkStreamMagCalReport4sendEv) -*(.text._ZN16PreFlightChecker27preFlightCheckHeadingFailedERK23estimator_innovations_sf) *(.text.imxrt_config_gpio) *(.text.nxsig_timeout) *(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_) -*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj23EEEff) +*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff) *(.text.dq_addlast) *(.text._ZN19MavlinkStreamVFRHUD4sendEv) *(.text.hrt_call_reschedule) @@ -487,14 +463,13 @@ *(.text._ZNK6matrix6MatrixIfLj3ELj1EE5emultERKS1_) *(.text.mallinfo_handler) *(.text._ZN13land_detector23MulticopterLandDetector14_update_topicsEv) -*(.text._ZN24ManualVelocitySmoothingZC1Ev) +*(.text._ZN24ManualVelocitySmoothingZC1Ev) /* itcm-check-ignore */ *(.text._ZN3ADC6sampleEj) *(.text._ZNK3Ekf22isTerrainEstimateValidEv) -*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) +*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) *(.text._ZN11ControlMath11addIfNotNanERff) *(.text._ZN9Commander21checkForMissionUpdateEv) *(.text._Z8set_tunei) -*(.text._ZN3Ekf13stopGpsFusionEv) *(.text._ZNK6matrix7Vector3IfE5crossERKNS_6MatrixIfLj3ELj1EEE) *(.text._ZN10FlightTask22_checkEkfResetCountersEv) *(.text._ZNK6matrix6MatrixIfLj3ELj1EE11isAllFiniteEv) @@ -516,7 +491,6 @@ *(.text.MEM_DataCopy2_2) *(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s) *(.text.sock_file_poll) -*(.text._ZN3Ekf20controlHaglRngFusionEv) *(.text._ZN10Ringbuffer9pop_frontEPhj) *(.text.nx_write) *(.text._ZN9Commander18manualControlCheckEv) @@ -527,18 +501,15 @@ *(.text.sem_clockwait) *(.text.inet_poll) *(.text._ZN6BMP3887collectEv) -*(.text._ZN15ArchPX4IOSerial19_do_rx_dma_callbackEbi) -*(.text._ZN15ArchPX4IOSerial10_abort_dmaEv) *(.text._ZNK15PositionControl24getLocalPositionSetpointER33vehicle_local_position_setpoint_s) *(.text._ZN3Ekf16controlGpsFusionERKN9estimator9imuSampleE) *(.text._ZN23MavlinkStreamRCChannels8get_sizeEv) *(.text._ZN20MavlinkStreamESCInfo8get_sizeEv) *(.text._ZNK6matrix6VectorIfLj2EE4normEv) *(.text._Z15arm_auth_updateyb) -*(.text._ZN3LED5ioctlEP4fileim) +*(.text._ZN3LED5ioctlEP4fileim) /* itcm-check-ignore */ *(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv) *(.text._ZN29MavlinkStreamLocalPositionNED4sendEv) -*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ILj3ELj1EEERKNS_5SliceIfLj2ELj1EXT_EXT0_EEE) *(.text._ZNK6matrix6VectorIfLj3EE3dotERKNS_6MatrixIfLj3ELj1EEE) *(.text.imxrt_lpi2c_setclock) *(.text._ZN6matrix12typeFunction9constrainIfEET_S2_S2_S2_.part.0) @@ -559,16 +530,13 @@ *(.text._ZN6BMP38815get_sensor_dataEhP9bmp3_data) *(.text._ZN18MavlinkRateLimiter5checkERKy) *(.text._ZThn24_N26MulticopterAttitudeControl3RunEv) -*(.text._ZN15ArchPX4IOSerial10_interruptEiPvS0_) *(.text.imxrt_periphclk_configure) -*(.text._ZN3Ekf8initHaglEv) *(.text._ZN4EKF218UpdateAuxVelSampleER17ekf2_timestamps_s) *(.text._ZN3RTL11on_inactiveEv) *(.text._ZN12FailsafeBase10modeCanRunERK16failsafe_flags_sh) *(.text._ZN4EKF216PublishEvPosBiasERKy) *(.text._ZN21MavlinkStreamAttitude8get_sizeEv) *(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv) -*(.text._ZN3Ekf24controlRangeHeightFusionEv) *(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf) *(.text._ZN12ModuleParamsD1Ev) @@ -586,22 +554,19 @@ *(.text._ZN26MulticopterPositionControl3RunEv) *(.text._ZN8Failsafe21fromQuadchuteActParamEi) *(.text._ZN24VariableLengthRingbuffer9pop_frontEPhj) -*(.text._ZN7control15BlockDerivative6updateEf) -*(.text._ZN5PX4IO10io_reg_getEhh) +*(.text._ZN7control15BlockDerivative6updateEf) /* itcm-check-ignore */ *(.text._ZN9Commander18safetyButtonUpdateEv) *(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report) *(.text._ZN18DataValidatorGroup16get_sensor_stateEj) *(.text.uart_xmitchars_done) *(.text._ZN4EKF225PublishYawEstimatorStatusERKy) *(.text.sin) -*(.text._ZN16PreFlightChecker27preFlightCheckVertVelFailedERK23estimator_innovations_sf) *(.text._ZN6Safety19safetyButtonHandlerEv) -*(.text._ZN3Ekf19controlAuxVelFusionEv) +*(.text._ZN3Ekf19controlAuxVelFusionERKN9estimator9imuSampleE) *(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_) *(.text._ZThn24_N7Sensors3RunEv) *(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ERKS1_) *(.text._ZN10FlightTask10reActivateEv) -*(.text._ZN5PX4IO17io_publish_raw_rcEv) *(.text._ZNK15PositionControl19getAttitudeSetpointER27vehicle_attitude_setpoint_s) *(.text._ZN4cdev4CDev4pollEP4fileP6pollfdb) *(.text._ZN9Commander20offboardControlCheckEv) @@ -613,7 +578,6 @@ *(.text._ZN8Failsafe17updateArmingStateERKybRK16failsafe_flags_s) *(.text.imxrt_lpi2c_modifyreg) *(.text.up_flush_dcache) -*(.text._ZN5PX4IO16io_handle_statusEt) *(.text._ZN15GyroCalibration3RunEv) *(.text.mavlink_start_uart_send) *(.text.MEM_DataCopy2) @@ -647,7 +611,6 @@ *(.text._ZN12FailsafeBase11updateDelayERKy) *(.text._ZN10FlightTask25_evaluateDistanceToGroundEv) *(.text._ZN4EKF218PublishGnssHgtBiasERKy) -*(.text._ZN3Ekf21controlHaglFlowFusionEv) *(.text._ZN6matrix6VectorIfLj3EE9normalizeEv) *(.text._ZThn16_N7sensors10VehicleIMU3RunEv) *(.text.__kernel_cos) @@ -659,22 +622,18 @@ *(.text._Z15blink_msg_statev) *(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report) *(.text._ZN8Failsafe14fromGfActParamEi) -*(.text._ZN3Ekf27checkAndFixCovarianceUpdateERKN6matrix12SquareMatrixIfLj23EEE) *(.text._ZN3Ekf17controlBetaFusionERKN9estimator9imuSampleE) -*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) +*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) /* itcm-check-ignore */ *(.text._ZN22MavlinkStreamHeartbeat8get_sizeEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEdVEf) *(.text._ZN17FlightTaskDescendC1Ev) *(.text._ZN26MavlinkStreamCameraTrigger8get_sizeEv) *(.text.iob_navail) *(.text._ZN12FailsafeBase25removeNonActivatedActionsEv) -*(.text._ZN16PreFlightChecker28preFlightCheckHorizVelFailedERK23estimator_innovations_sf) *(.text._ZN15TakeoffHandling10updateRampEff) *(.text._Z7led_offi) -*(.text._ZN16PreFlightChecker22selectHeadingTestLimitEv) *(.text.led_off) *(.text.udp_wrbuffer_test) -*(.text._ZNK3Ekf34updateVerticalPositionAidSrcStatusERKyfffR24estimator_aid_source1d_s) *(.text._ZNK4math17WelfordMeanVectorIfLj3EE8varianceEv) *(.text._ZN27MavlinkStreamAttitudeTarget4sendEv) *(.text._ZN12MixingOutput19updateSubscriptionsEb) @@ -683,7 +642,6 @@ *(.text._ZN18MavlinkStreamDebug8get_sizeEv) *(.text._ZN12GPSDriverUBX7receiveEj) *(.text._ZN13BatteryStatus21parameter_update_pollEb) -*(.text._ZN3Ekf26checkYawAngleObservabilityEv) *(.text._ZN3RTL18updateDatamanCacheEv) *(.text.__ieee754_sqrtf) *(.text._ZThn24_N18mag_bias_estimator16MagBiasEstimator3RunEv) @@ -701,11 +659,9 @@ *(.text._ZN12SystemChecks14checkAndReportERK7ContextR6Report) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1EPKf) *(.text.imxrt_padmux_address) -*(.text._ZN3Ekf15setVelPosStatusEib) *(.text._ZN19MavlinkStreamVFRHUD8get_sizeEv) *(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes) *(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report) -*(.text._ZN17ObstacleAvoidanceD1Ev) *(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv) *(.text.MEM_DataCopy2_1) *(.text._ZN6BMP3887measureEv) @@ -713,7 +669,7 @@ *(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv) *(.text._ZN28MavlinkStreamEstimatorStatus8get_sizeEv) *(.text.up_clean_dcache) -*(.text._ZThn56_N26MulticopterPositionControl3RunEv) +*(.text._ZThn24_N26MulticopterPositionControl3RunEv) *(.text._ZN16FlightTimeChecks14checkAndReportERK7ContextR6Report) *(.text._ZN13ManualControl12processInputEy) *(.text._ZN17CpuResourceChecks14checkAndReportERK7ContextR6Report) @@ -725,9 +681,8 @@ *(.text._ZN32MavlinkStreamNavControllerOutput8get_sizeEv) *(.text._ZN6matrix8wrap_2piIfEET_S1_) *(.text._ZN4uORB7Manager30orb_remove_internal_subscriberEPv) -*(.text._ZN10BMP388_I2C7get_regEh) +*(.text._ZN10BMP388_I2C7get_regEhPh) *(.text._ZN4math17WelfordMeanVectorIfLj3EE5resetEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition10const_rateEv) *(.text._ZN27MavlinkStreamScaledPressure8get_sizeEv) *(.text._ZN3RTL17parameters_updateEv) *(.text._ZN18EstimatorInterface11setBaroDataERKN9estimator10baroSampleE.part.0) @@ -741,7 +696,6 @@ *(.text._ZN4uORB10DeviceNode10poll_stateEP4file) *(.text._ZN4uORB7Manager8orb_copyEPK12orb_metadataiPv) *(.text._ZN27MavlinkStreamServoOutputRawILi0EE8get_sizeEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition8get_sizeEv) *(.text._ZN8Geofence3runEv) *(.text._ZN15EstimatorChecks25checkEstimatorStatusFlagsERK7ContextR6ReportRK18estimator_status_sRK24vehicle_local_position_s) *(.text._ZN18MagnetometerChecks14checkAndReportERK7ContextR6Report) @@ -752,7 +706,6 @@ *(.text.read) *(.text._ZN4uORB15PublicationBaseD1Ev) *(.text._ZN22MavlinkStreamDebugVect8get_sizeEv) -*(.text._ZN22MavlinkStreamCollision8get_sizeEv) *(.text._ZN7Mission11on_inactiveEv) *(.text._ZN7sensors19VehicleMagnetometer20UpdateMagCalibrationEv) *(.text._ZN11calibration27FindCurrentCalibrationIndexEPKcm) diff --git a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld index 2f6259209a..a14521a6b5 100644 --- a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld +++ b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld @@ -3,7 +3,6 @@ *(.text.arm_doirq) *(.text.arm_svcall) *(.text.arm_switchcontext) -*(.text.board_autoled_on) *(.text.clock_timer) *(.text.exception_common) *(.text.flexio_irq_handler) @@ -20,7 +19,6 @@ *(.text.imxrt_endwait) *(.text.imxrt_enet_interrupt) *(.text.imxrt_enet_interrupt_work) -*(.text.imxrt_gpio3_16_31_interrupt) *(.text.imxrt_interrupt) *(.text.imxrt_lpi2c_isr) *(.text.imxrt_lpspi_exchange) @@ -105,13 +103,12 @@ *(.text.devif_event_trigger) *(.text.devif_poll_icmp) *(.text.icmp_poll) -*(.text.devif_packet_conversion) *(.text.arp_out) *(.text.arp_find) *(.text.arp_format) -*(.text.net_ipv4addr_hdrcmp) -*(.text.net_ipv4addr_copy) -*(.text.net_ipv4addr_broadcast) +*(.text.net_ipv4addr_hdrcmp) /* itcm-check-ignore */ +*(.text.net_ipv4addr_copy) /* itcm-check-ignore */ +*(.text.net_ipv4addr_broadcast) /* itcm-check-ignore */ *(.text.wd_start) *(.text.arp_arpin) *(.text.ipv4_input) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld index 0a4e0faa6a..a52a3b46b0 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld @@ -2,7 +2,7 @@ *(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) *(.text._ZN13MavlinkStream6updateERKy) *(.text._ZN7Mavlink16update_rate_multEv) -*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) +*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) /* itcm-check-ignore */ *(.text._ZN13MavlinkStream12get_size_avgEv) *(.text._ZN16ControlAllocator3RunEv) *(.text._ZN22MulticopterRateControl3RunEv.part.0) @@ -57,7 +57,6 @@ *(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE) *(.text._ZN4EKF220PublishLocalPositionERKy) *(.text._mav_finalize_message_chan_send) -*(.text._ZN3Ekf19fixCovarianceErrorsEb) *(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb) *(.text._ZN6events12SendProtocol6updateERKy) *(.text._ZN6device3SPI8transferEPhS1_j) @@ -68,7 +67,7 @@ *(.text.nx_poll) *(.text._ZN15MavlinkReceiver3runEv) *(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh) -*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEES8_S8_S8_) +*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_) *(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE) *(.text._ZN3px46logger6Logger3runEv) *(.text._ZN4uORB20SubscriptionInterval7updatedEv) @@ -122,7 +121,6 @@ *(.text._ZN22MulticopterRateControl28updateActuatorControlsStatusERK25vehicle_torque_setpoint_sf) *(.text._ZN11RateControl6updateERKN6matrix7Vector3IfEES4_S4_fb) *(.text._ZN39ControlAllocationSequentialDesaturation19desaturateActuatorsERN6matrix6VectorIfLj16EEERKS2_b) -*(.text._ZN22MavlinkStreamCollision4sendEv) *(.text.imxrt_lpi2c_transfer) *(.text.uart_putxmitchar) *(.text.clock_nanosleep) @@ -166,7 +164,7 @@ *(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv) *(.text.imxrt_dmach_start) *(.text._ZN3ADC19update_system_powerEy) -*(.text._ZNK3Ekf19get_ekf_soln_statusEPt) +*(.text._ZNK3Ekf19get_ekf_soln_statusEv) *(.text._ZN3px46logger15watchdog_updateERNS0_15watchdog_data_tEb) *(.text.imxrt_gpio_read) *(.text._ZN32MavlinkStreamNavControllerOutput4sendEv) @@ -193,11 +191,10 @@ *(.text._ZN22MavlinkStreamGPSStatus4sendEv) *(.text._ZN4EKF220UpdateAirspeedSampleER17ekf2_timestamps_s) *(.text._ZN23MavlinkStreamStatustext4sendEv) -*(.text._ZN3Ekf15constrainStatesEv) *(.text._ZN12PX4IO_serial4readEjPvj) *(.text.uart_poll) *(.text._ZN24MavlinkParametersManager4sendEv) -*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_s) +*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_sf) *(.text.file_poll) *(.text.hrt_elapsed_time) *(.text._ZN7Mavlink11send_finishEv) @@ -231,8 +228,7 @@ *(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE) *(.text.imxrt_queuedtd) *(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv) -*(.text._ZN3Ekf16fuseVelPosHeightEffi) -*(.text._ZN3Ekf23controlBaroHeightFusionEv) +*(.text._ZN3Ekf23controlBaroHeightFusionERKN9estimator9imuSampleE) *(.text._ZN16PX4Accelerometer9set_scaleEf) *(.text._ZN11ControlMath11constrainXYERKN6matrix7Vector2IfEES4_RKf) *(.text._ZN22MavlinkStreamEfiStatus4sendEv) @@ -242,13 +238,11 @@ *(.text._ZN15PositionControl11_inputValidEv) *(.text._ZN7sensors14VehicleAirData3RunEv) *(.text.perf_count) -*(.text._ZN3Ekf16controlMagFusionEv) +*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE) *(.text.pthread_sem_give) *(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb) -*(.text._ZN30MavlinkStreamUTMGlobalPosition4sendEv) *(.text._ZN4uORB20SubscriptionInterval4copyEPv) *(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv) -*(.text._ZN17ObstacleAvoidanceC1EP12ModuleParams) *(.text.imxrt_epcomplete.constprop.0) *(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_) *(.text._ZN9Commander30handleModeIntentionAndFailsafeEv) @@ -279,7 +273,7 @@ *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_) *(.text.udp_pollsetup) *(.text._ZL14timer_callbackPv) -*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj23EEEf) +*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf) *(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi) *(.text.nxsem_wait_irq) *(.text._ZN20MavlinkCommandSender4lockEv) @@ -298,7 +292,7 @@ *(.text._ZN25MavlinkStreamHomePosition4sendEv) *(.text._ZN24MavlinkParametersManager8send_oneEv) *(.text._ZN15OutputPredictor29applyCorrectionToOutputBufferERKN6matrix7Vector3IfEES4_) -*(.text._ZN21HealthAndArmingChecks6updateEb) +*(.text._ZN21HealthAndArmingChecks6updateEbb) *(.text._ZThn24_N22MulticopterRateControl3RunEv) *(.text._ZN26MavlinkStreamManualControl4sendEv) *(.text._ZN27MavlinkStreamOpticalFlowRad4sendEv) @@ -307,13 +301,11 @@ *(.text._ZN24MavlinkParametersManager18send_untransmittedEv) *(.text._ZN10MavlinkFTP4sendEv) *(.text._ZN15ArchPX4IOSerial13_do_interruptEv) -*(.text._ZN3Ekf27controlExternalVisionFusionEv) +*(.text._ZN3Ekf27controlExternalVisionFusionERKN9estimator9imuSampleE) *(.text.clock_gettime) *(.text._ZN3ADC17update_adc_reportEy) -*(.text._ZN3sym25ComputeYaw312InnovVarAndHIfEEvRKN6matrix6MatrixIT_Lj24ELj1EEERKNS2_IS3_Lj23ELj23EEES3_S3_PS3_PNS2_IS3_Lj23ELj1EEE) -*(.text._ZN3Ekf19runTerrainEstimatorERKN9estimator9imuSampleE) *(.text._ZN32MavlinkStreamGimbalManagerStatus4sendEv) -*(.text._ZN9LockGuardD1Ev) +*(.text._ZN9LockGuardD1Ev) /* itcm-check-ignore */ *(.text._ZN4EKF213PublishStatesERKy) *(.text._ZN3ADC3RunEv) *(.text._ZN6BMP38815compensate_dataEhPK16bmp3_uncomp_dataP9bmp3_data) @@ -348,7 +340,7 @@ *(.text._ZN15FailureDetector6updateERK16vehicle_status_sRK22vehicle_control_mode_s) *(.text._ZN7Mavlink10send_startEi) *(.text.imxrt_lpspi_setbits) -*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEf) +*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEff) *(.text._ZN4EKF222UpdateAccelCalibrationERKy) *(.text._ZN7sensors19VehicleMagnetometer3RunEv) *(.text._ZN29MavlinkStreamMountOrientation4sendEv) @@ -363,15 +355,13 @@ *(.text.poll) *(.text._ZN14FlightTaskAutoD1Ev) *(.text._ZN4uORB10DeviceNode22get_initial_generationEv) -*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator9gpsSampleE) +*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator10gnssSampleE) *(.text._ZN3Ekf40updateOnGroundMotionForOpticalFlowChecksEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1Ev) *(.text._ZN14ZeroGyroUpdate6updateER3EkfRKN9estimator9imuSampleE) *(.text._ZN30MavlinkStreamOpenDroneIdSystem4sendEv) *(.text._ZN22MavlinkStreamScaledIMU4sendEv) -*(.text._ZN46MavlinkStreamTrajectoryRepresentationWaypoints4sendEv) *(.text.imxrt_ioctl) -*(.text._ZN3Ekf25checkMagBiasObservabilityEv) *(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv) *(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0) *(.text._ZN19StickAccelerationXYC1EP12ModuleParams) @@ -401,7 +391,7 @@ *(.text._ZN9Commander11updateTunesEv) *(.text._ZN4EKF215UpdateMagSampleER17ekf2_timestamps_s) *(.text._ZN18DataValidatorGroup3putEjyPKfmh) -*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_) +*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_S0_) *(.text._ZN12FailsafeBase13checkFailsafeEibbRKNS_13ActionOptionsE) *(.text._ZN17FlightTaskDescendD1Ev) *(.text._ZN30MavlinkStreamOpenDroneIdSystem8get_sizeEv) @@ -409,7 +399,6 @@ *(.text._ZN24FlightTaskManualAltitudeD1Ev) *(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb) *(.text.uart_pollnotify) -*(.text._ZN3Ekf11predictHaglERKN9estimator9imuSampleE) *(.text._ZN4EKF215PublishBaroBiasERKy) *(.text._ZN4EKF221UpdateGyroCalibrationERKy) *(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) @@ -440,7 +429,7 @@ *(.text.clock_systime_timespec) *(.text._ZN4uORB10DeviceNode26remove_internal_subscriberEv) *(.text._ZThn16_N4EKF23RunEv) -*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj23EEE) +*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj24EEE) *(.text._ZN12ActuatorTest6updateEif) *(.text._ZN17VelocitySmoothingC1Efff) *(.text._ZN13AnalogBattery19get_voltage_channelEv) @@ -458,7 +447,7 @@ *(.text.imxrt_config_gpio) *(.text.nxsig_timeout) *(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_) -*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj23EEEff) +*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff) *(.text.dq_addlast) *(.text._ZN19MavlinkStreamVFRHUD4sendEv) *(.text.hrt_call_reschedule) @@ -482,14 +471,13 @@ *(.text._ZNK6matrix6MatrixIfLj3ELj1EE5emultERKS1_) *(.text.mallinfo_handler) *(.text._ZN13land_detector23MulticopterLandDetector14_update_topicsEv) -*(.text._ZN24ManualVelocitySmoothingZC1Ev) +*(.text._ZN24ManualVelocitySmoothingZC1Ev) /* itcm-check-ignore */ *(.text._ZN3ADC6sampleEj) *(.text._ZNK3Ekf22isTerrainEstimateValidEv) -*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) +*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) *(.text._ZN11ControlMath11addIfNotNanERff) *(.text._ZN9Commander21checkForMissionUpdateEv) *(.text._Z8set_tunei) -*(.text._ZN3Ekf13stopGpsFusionEv) *(.text._ZNK6matrix7Vector3IfE5crossERKNS_6MatrixIfLj3ELj1EEE) *(.text._ZN10FlightTask22_checkEkfResetCountersEv) *(.text._ZNK6matrix6MatrixIfLj3ELj1EE11isAllFiniteEv) @@ -511,7 +499,6 @@ *(.text.MEM_DataCopy2_2) *(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s) *(.text.sock_file_poll) -*(.text._ZN3Ekf20controlHaglRngFusionEv) *(.text._ZN10Ringbuffer9pop_frontEPhj) *(.text.nx_write) *(.text._ZN9Commander18manualControlCheckEv) @@ -533,7 +520,6 @@ *(.text._ZN3LED5ioctlEP4fileim) *(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv) *(.text._ZN29MavlinkStreamLocalPositionNED4sendEv) -*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ILj3ELj1EEERKNS_5SliceIfLj2ELj1EXT_EXT0_EEE) *(.text._ZNK6matrix6VectorIfLj3EE3dotERKNS_6MatrixIfLj3ELj1EEE) *(.text.imxrt_lpi2c_setclock) *(.text._ZN6matrix12typeFunction9constrainIfEET_S2_S2_S2_.part.0) @@ -556,14 +542,12 @@ *(.text._ZThn24_N26MulticopterAttitudeControl3RunEv) *(.text._ZN15ArchPX4IOSerial10_interruptEiPvS0_) *(.text.imxrt_periphclk_configure) -*(.text._ZN3Ekf8initHaglEv) *(.text._ZN4EKF218UpdateAuxVelSampleER17ekf2_timestamps_s) *(.text._ZN3RTL11on_inactiveEv) *(.text._ZN12FailsafeBase10modeCanRunERK16failsafe_flags_sh) *(.text._ZN4EKF216PublishEvPosBiasERKy) *(.text._ZN21MavlinkStreamAttitude8get_sizeEv) *(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv) -*(.text._ZN3Ekf24controlRangeHeightFusionEv) *(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf) *(.text._ZN12ModuleParamsD1Ev) @@ -581,7 +565,7 @@ *(.text._ZN26MulticopterPositionControl3RunEv) *(.text._ZN8Failsafe21fromQuadchuteActParamEi) *(.text._ZN24VariableLengthRingbuffer9pop_frontEPhj) -*(.text._ZN7control15BlockDerivative6updateEf) +*(.text._ZN7control15BlockDerivative6updateEf) /* itcm-check-ignore */ *(.text._ZN5PX4IO10io_reg_getEhh) *(.text._ZN9Commander18safetyButtonUpdateEv) *(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report) @@ -590,7 +574,7 @@ *(.text._ZN4EKF225PublishYawEstimatorStatusERKy) *(.text.sin) *(.text._ZN6Safety19safetyButtonHandlerEv) -*(.text._ZN3Ekf19controlAuxVelFusionEv) +*(.text._ZN3Ekf19controlAuxVelFusionERKN9estimator9imuSampleE) *(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_) *(.text._ZThn24_N7Sensors3RunEv) *(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ERKS1_) @@ -641,7 +625,6 @@ *(.text._ZN12FailsafeBase11updateDelayERKy) *(.text._ZN10FlightTask25_evaluateDistanceToGroundEv) *(.text._ZN4EKF218PublishGnssHgtBiasERKy) -*(.text._ZN3Ekf21controlHaglFlowFusionEv) *(.text._ZN6matrix6VectorIfLj3EE9normalizeEv) *(.text._ZThn16_N7sensors10VehicleIMU3RunEv) *(.text.__kernel_cos) @@ -653,9 +636,8 @@ *(.text._Z15blink_msg_statev) *(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report) *(.text._ZN8Failsafe14fromGfActParamEi) -*(.text._ZN3Ekf27checkAndFixCovarianceUpdateERKN6matrix12SquareMatrixIfLj23EEE) *(.text._ZN3Ekf17controlBetaFusionERKN9estimator9imuSampleE) -*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) +*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) /* itcm-check-ignore */ *(.text._ZN22MavlinkStreamHeartbeat8get_sizeEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEdVEf) *(.text._ZN17FlightTaskDescendC1Ev) @@ -666,7 +648,6 @@ *(.text._Z7led_offi) *(.text.led_off) *(.text.udp_wrbuffer_test) -*(.text._ZNK3Ekf34updateVerticalPositionAidSrcStatusERKyfffR24estimator_aid_source1d_s) *(.text._ZNK4math17WelfordMeanVectorIfLj3EE8varianceEv) *(.text._ZN27MavlinkStreamAttitudeTarget4sendEv) *(.text._ZN12MixingOutput19updateSubscriptionsEb) @@ -692,11 +673,9 @@ *(.text._ZN12SystemChecks14checkAndReportERK7ContextR6Report) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1EPKf) *(.text.imxrt_padmux_address) -*(.text._ZN3Ekf15setVelPosStatusEib) *(.text._ZN19MavlinkStreamVFRHUD8get_sizeEv) *(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes) *(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report) -*(.text._ZN17ObstacleAvoidanceD1Ev) *(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv) *(.text.MEM_DataCopy2_1) *(.text._ZN6BMP3887measureEv) @@ -704,7 +683,7 @@ *(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv) *(.text._ZN28MavlinkStreamEstimatorStatus8get_sizeEv) *(.text.up_clean_dcache) -*(.text._ZThn56_N26MulticopterPositionControl3RunEv) +*(.text._ZThn24_N26MulticopterPositionControl3RunEv) *(.text._ZN16FlightTimeChecks14checkAndReportERK7ContextR6Report) *(.text._ZN13ManualControl12processInputEy) *(.text._ZN17CpuResourceChecks14checkAndReportERK7ContextR6Report) @@ -716,9 +695,8 @@ *(.text._ZN32MavlinkStreamNavControllerOutput8get_sizeEv) *(.text._ZN6matrix8wrap_2piIfEET_S1_) *(.text._ZN4uORB7Manager30orb_remove_internal_subscriberEPv) -*(.text._ZN10BMP388_I2C7get_regEh) +*(.text._ZN10BMP388_I2C7get_regEhPh) *(.text._ZN4math17WelfordMeanVectorIfLj3EE5resetEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition10const_rateEv) *(.text._ZN27MavlinkStreamScaledPressure8get_sizeEv) *(.text._ZN3RTL17parameters_updateEv) *(.text._ZN18EstimatorInterface11setBaroDataERKN9estimator10baroSampleE.part.0) @@ -732,7 +710,6 @@ *(.text._ZN4uORB10DeviceNode10poll_stateEP4file) *(.text._ZN4uORB7Manager8orb_copyEPK12orb_metadataiPv) *(.text._ZN27MavlinkStreamServoOutputRawILi0EE8get_sizeEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition8get_sizeEv) *(.text._ZN8Geofence3runEv) *(.text._ZN15EstimatorChecks25checkEstimatorStatusFlagsERK7ContextR6ReportRK18estimator_status_sRK24vehicle_local_position_s) *(.text._ZN18MagnetometerChecks14checkAndReportERK7ContextR6Report) @@ -743,7 +720,6 @@ *(.text.read) *(.text._ZN4uORB15PublicationBaseD1Ev) *(.text._ZN22MavlinkStreamDebugVect8get_sizeEv) -*(.text._ZN22MavlinkStreamCollision8get_sizeEv) *(.text._ZN7Mission11on_inactiveEv) *(.text._ZN7sensors19VehicleMagnetometer20UpdateMagCalibrationEv) *(.text._ZN11calibration27FindCurrentCalibrationIndexEPKcm) From 0f2012ba06b5c7efccd84deaa8ea59aa260c48c4 Mon Sep 17 00:00:00 2001 From: Michael Smith <36905981+michael-f-smith@users.noreply.github.com> Date: Mon, 19 May 2025 20:01:02 -0400 Subject: [PATCH 008/130] MSP_OSD Update: Add original battery status msg. (#24872) Co-authored-by: Michael --- src/drivers/osd/msp_osd/msp_osd.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/drivers/osd/msp_osd/msp_osd.cpp b/src/drivers/osd/msp_osd/msp_osd.cpp index 25b9aa7c96..e3a6b3838c 100644 --- a/src/drivers/osd/msp_osd/msp_osd.cpp +++ b/src/drivers/osd/msp_osd/msp_osd.cpp @@ -341,6 +341,9 @@ void MspOsd::Run() battery_status_s battery_status{}; _battery_status_sub.copy(&battery_status); + const auto msg_original = msp_osd::construct_BATTERY_STATE(battery_status); + this->Send(MSP_BATTERY_STATE, &msg_original); + const auto msg = msp_osd::construct_rendor_BATTERY_STATE(battery_status); this->Send(MSP_CMD_DISPLAYPORT, &msg, sizeof(msp_rendor_battery_state_t)); From c2f872c558932a6d3c8b03497a28b05da92c1046 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Tue, 20 May 2025 15:34:20 +1000 Subject: [PATCH 009/130] docs: put RC modules into their own category (#24847) --- Tools/px4moduledoc/markdownout.py | 22 +++++++++++----------- Tools/px4moduledoc/srcparser.py | 4 ++-- src/drivers/rc/crsf_rc/CrsfRc.cpp | 1 + src/drivers/rc/dsm_rc/DsmRc.cpp | 1 + src/drivers/rc/ghst_rc/GhstRc.cpp | 1 + src/drivers/rc/sbus_rc/SbusRc.cpp | 1 + src/drivers/rc_input/RCInput.cpp | 1 + 7 files changed, 18 insertions(+), 13 deletions(-) diff --git a/Tools/px4moduledoc/markdownout.py b/Tools/px4moduledoc/markdownout.py index 469e031a63..783ee620b0 100644 --- a/Tools/px4moduledoc/markdownout.py +++ b/Tools/px4moduledoc/markdownout.py @@ -40,25 +40,25 @@ The generated files will be written to the `modules` directory. ## Categories """ for category in sorted(module_groups): - result += "- [%s](modules_%s.md)\n" % (category.capitalize(), category) + result += f"- [{category.capitalize()}](modules_{category}.md)\n" self._outputs['main'] = result for category in sorted(module_groups): - result = "# Modules Reference: %s\n" % category.capitalize() + result = f"# Modules Reference: {category.capitalize()}\n\n" subcategories = module_groups[category] + if len(subcategories) > 1: - result += 'Subcategories:\n' - for subcategory in subcategories: + result += 'Subcategories:\n\n' + for subcategory in sorted(subcategories): if subcategory == '': continue subcategory_label = subcategory.replace('_', ' ').title() subcategory_file_name = category+'_'+subcategory - result += '- [%s](modules_%s.md)\n' % (subcategory_label, subcategory_file_name) + result += f'- [{subcategory_label}](modules_{subcategory_file_name}.md)\n' # add a sub-page for the subcategory - result_subpage = '# Modules Reference: %s (%s)\n' % \ - (subcategory_label, category.capitalize()) + result_subpage = f'# Modules Reference: {subcategory_label} ({category.capitalize()})\n' result_subpage += self._ProcessModules(subcategories[subcategory]) self._outputs[subcategory_file_name] = result_subpage @@ -68,14 +68,14 @@ The generated files will be written to the `modules` directory. def _ProcessModules(self, module_list): result = '' for module in module_list: - result += "## %s\n" % module.name() - result += "Source: [%s](https://github.com/PX4/PX4-Autopilot/tree/main/src/%s)\n\n" % (module.scope(), module.scope()) + result += f"\n## {module.name()}\n\n" + result += f"Source: [{module.scope()}](https://github.com/PX4/PX4-Autopilot/tree/main/src/{module.scope()})\n\n" doc = module.documentation() if len(doc) > 0: - result += "%s\n" % doc + result += f"{doc}\n" usage_string = module.usage_string() if len(usage_string) > 0: - result += '\n### Usage\n```\n%s\n```\n' % (module.name(), usage_string) + result += f'### Usage {{#{module.name()}_usage}}\n\n```\n{usage_string}\n```\n' return result def Save(self, dirname): diff --git a/Tools/px4moduledoc/srcparser.py b/Tools/px4moduledoc/srcparser.py index 4937f67b7e..8b56e7bb08 100644 --- a/Tools/px4moduledoc/srcparser.py +++ b/Tools/px4moduledoc/srcparser.py @@ -12,11 +12,11 @@ class ModuleDocumentation(object): """ # If you add categories or subcategories, they also need to be added to the - # TOC in https://github.com/PX4/PX4-user_guide/blob/main/en/SUMMARY.md + # TOC in https://github.com/PX4/PX4-Autopilot/blob/main/docs/en/SUMMARY.md valid_categories = ['driver', 'estimator', 'controller', 'system', 'communication', 'command', 'template', 'simulation', 'autotune'] valid_subcategories = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor', - 'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder'] + 'magnetometer', 'baro', 'optical_flow', 'radio_control','rpm_sensor', 'transponder'] max_line_length = 80 # wrap lines that are longer than this diff --git a/src/drivers/rc/crsf_rc/CrsfRc.cpp b/src/drivers/rc/crsf_rc/CrsfRc.cpp index 3ea6c0ac27..d7401f57ae 100644 --- a/src/drivers/rc/crsf_rc/CrsfRc.cpp +++ b/src/drivers/rc/crsf_rc/CrsfRc.cpp @@ -526,6 +526,7 @@ This module parses the CRSF RC uplink protocol and generates CRSF downlink telem )DESCR_STR"); PRINT_MODULE_USAGE_NAME("crsf_rc", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("radio_control"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); diff --git a/src/drivers/rc/dsm_rc/DsmRc.cpp b/src/drivers/rc/dsm_rc/DsmRc.cpp index f35bc4487f..b12fbfedcc 100644 --- a/src/drivers/rc/dsm_rc/DsmRc.cpp +++ b/src/drivers/rc/dsm_rc/DsmRc.cpp @@ -399,6 +399,7 @@ This module does Spektrum DSM RC input parsing. )DESCR_STR"); PRINT_MODULE_USAGE_NAME("dsm_rc", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("radio_control"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); diff --git a/src/drivers/rc/ghst_rc/GhstRc.cpp b/src/drivers/rc/ghst_rc/GhstRc.cpp index 1aa3c23e89..aa4525d64c 100644 --- a/src/drivers/rc/ghst_rc/GhstRc.cpp +++ b/src/drivers/rc/ghst_rc/GhstRc.cpp @@ -292,6 +292,7 @@ This module does Ghost (GHST) RC input parsing. )DESCR_STR"); PRINT_MODULE_USAGE_NAME("ghst_rc", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("radio_control"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); diff --git a/src/drivers/rc/sbus_rc/SbusRc.cpp b/src/drivers/rc/sbus_rc/SbusRc.cpp index 12d57da141..2ebdcfa207 100644 --- a/src/drivers/rc/sbus_rc/SbusRc.cpp +++ b/src/drivers/rc/sbus_rc/SbusRc.cpp @@ -302,6 +302,7 @@ This module does SBUS RC input parsing. )DESCR_STR"); PRINT_MODULE_USAGE_NAME("sbus_rc", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("radio_control"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index a86ade0ad0..214853f647 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -1018,6 +1018,7 @@ This module does the RC input parsing and auto-selecting the method. Supported m )DESCR_STR"); PRINT_MODULE_USAGE_NAME("rc_input", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("radio_control"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "", "RC device", true); From 9e45f077b189806bdd1b1ef1d2b3b6fe5e99f3aa Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Tue, 20 May 2025 12:00:29 +0200 Subject: [PATCH 010/130] add flash-analysis for auterion_fmu-v6s board (#24885) --- boards/auterion/fmu-v6s/flash-analysis.px4board | 1 + .../fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld | 6 ++++++ 2 files changed, 7 insertions(+) create mode 100644 boards/auterion/fmu-v6s/flash-analysis.px4board create mode 100644 boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld diff --git a/boards/auterion/fmu-v6s/flash-analysis.px4board b/boards/auterion/fmu-v6s/flash-analysis.px4board new file mode 100644 index 0000000000..30717ad93c --- /dev/null +++ b/boards/auterion/fmu-v6s/flash-analysis.px4board @@ -0,0 +1 @@ +CONFIG_BOARD_LINKER_PREFIX="flash-analysis" diff --git a/boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld b/boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld new file mode 100644 index 0000000000..5df2f5180a --- /dev/null +++ b/boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld @@ -0,0 +1,6 @@ +INCLUDE "script.ld" + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 10080K +} From 0b3fc0a62d2db9a94b5e4f493fa5d2aee7f83400 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 12 May 2025 18:57:29 +0200 Subject: [PATCH 011/130] SIH: add Hexacopter X to enable easy simulation of a motor failure. --- .../init.d-posix/airframes/10044_sihsim_hex | 47 +++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + docs/en/sim_sih/index.md | 18 +++++-- .../community_supported_simulators.md | 2 +- .../simulation/simulator_sih/CMakeLists.txt | 1 + src/modules/simulation/simulator_sih/sih.cpp | 40 ++++++++++++---- src/modules/simulation/simulator_sih/sih.hpp | 9 ++-- .../simulation/simulator_sih/sih_params.c | 7 +-- 8 files changed, 101 insertions(+), 24 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/10044_sihsim_hex diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10044_sihsim_hex b/ROMFS/px4fmu_common/init.d-posix/airframes/10044_sihsim_hex new file mode 100644 index 0000000000..36ae9a26d7 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10044_sihsim_hex @@ -0,0 +1,47 @@ +#!/bin/sh +# +# @name HexarotorX SITL for SIH +# +# @type Hexarotor x +# @class Copter +# +# @maintainer Matthias Grob +# + +. ${R}etc/init.d/rc.mc_defaults + +PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim} +PX4_SIM_MODEL=${PX4_SIM_MODEL:=hex} + +param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 1 +param set-default SENS_EN_MAGSIM 1 + +param set SIH_VEHICLE_TYPE 4 + +# Symmetric hexacopter X clockwise motor numbering +param set-default CA_ROTOR_COUNT 6 +param set-default CA_ROTOR0_PX 0.866 +param set-default CA_ROTOR0_PY 0.5 +param set-default CA_ROTOR1_PX 0 +param set-default CA_ROTOR1_PY 1 +param set-default CA_ROTOR1_KM -0.05 +param set-default CA_ROTOR2_PX -0.866 +param set-default CA_ROTOR2_PY 0.5 +param set-default CA_ROTOR3_PX -0.866 +param set-default CA_ROTOR3_PY -0.5 +param set-default CA_ROTOR3_KM -0.05 +param set-default CA_ROTOR4_PX 0 +param set-default CA_ROTOR4_PY -1 +param set-default CA_ROTOR5_PX 0.866 +param set-default CA_ROTOR5_PY -0.5 +param set-default CA_ROTOR5_KM -0.05 + +param set-default PWM_MAIN_FUNC1 101 +param set-default PWM_MAIN_FUNC2 102 +param set-default PWM_MAIN_FUNC3 103 +param set-default PWM_MAIN_FUNC4 104 +param set-default PWM_MAIN_FUNC5 105 +param set-default PWM_MAIN_FUNC6 106 + +param set-default EKF2_GPS_DELAY 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index b4e107799f..ff72e5e468 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -109,6 +109,7 @@ px4_add_romfs_files( 10041_sihsim_airplane 10042_sihsim_xvert 10043_sihsim_standard_vtol + 10044_sihsim_hex 17001_flightgear_tf-g1 17002_flightgear_tf-g2 diff --git a/docs/en/sim_sih/index.md b/docs/en/sim_sih/index.md index 9bbd356d98..9f27250f1e 100644 --- a/docs/en/sim_sih/index.md +++ b/docs/en/sim_sih/index.md @@ -58,6 +58,7 @@ To set up/start SIH: 1. Open QGroundControl and wait for the flight controller too boot and connect. 1. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame: - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) + - SIH Hexacopter X currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently. - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) @@ -114,25 +115,31 @@ To run SIH as SITL: 1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md). 1. Run the appropriate make command for each vehicle type (at the root of the PX4-Autopilot repository): - - quadrotor: + - Quadcopter ```sh make px4_sitl sihsim_quadx ``` - - Fixed-wing (plane): + - Hexacopter + + ```sh + make px4_sitl sihsim_hex + ``` + + - Fixed-wing (plane) ```sh make px4_sitl sihsim_airplane ``` - - XVert VTOL tailsitter: + - XVert VTOL tailsitter ```sh make px4_sitl sihsim_xvert ``` - - Standard VTOL: + - Standard VTOL ```sh make px4_sitl sihsim_standard_vtol @@ -231,7 +238,8 @@ For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init. The dynamic models for the various vehicles are: -- Quadrotor: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). +- Quadcopter: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). +- Hexacopter: Equivalent to the Quadcopter but with a symmetric hexacopter x actuation setup. - Fixed-wing: Inspired by the PhD thesis: "Dynamics modeling of agile fixed-wing unmanned aerial vehicles." Khan, Waqas, supervised by Nahon, Meyer, McGill University, PhD thesis, 2016. - Tailsitter: Inspired by the master's thesis: "Modeling and control of a flying wing tailsitter unmanned aerial vehicle." Chiappinelli, Romain, supervised by Nahon, Meyer, McGill University, Masters thesis, 2018. diff --git a/docs/en/simulation/community_supported_simulators.md b/docs/en/simulation/community_supported_simulators.md index 6aec7dba67..79f176ea72 100644 --- a/docs/en/simulation/community_supported_simulators.md +++ b/docs/en/simulation/community_supported_simulators.md @@ -14,8 +14,8 @@ Questions about these tools should be raised on the [discussion forums](../contr | Simulator | Description | | ---------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL

| | [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| | [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| | [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| | [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a very significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| -| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

An alternative to HITL that offers a hard real-time simulation directly on the hardware autopilot. This simulator is implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih).

Supported Vehicles: Plane, Quad, Tailsitter, Standard VTOL

| diff --git a/src/modules/simulation/simulator_sih/CMakeLists.txt b/src/modules/simulation/simulator_sih/CMakeLists.txt index 7ae8483c51..0be8db3c1b 100644 --- a/src/modules/simulation/simulator_sih/CMakeLists.txt +++ b/src/modules/simulation/simulator_sih/CMakeLists.txt @@ -54,6 +54,7 @@ if(PX4_PLATFORM MATCHES "posix") quadx xvert standard_vtol + hex ) # find corresponding airframes diff --git a/src/modules/simulation/simulator_sih/sih.cpp b/src/modules/simulation/simulator_sih/sih.cpp index 30ac027d6f..32b973c3f8 100644 --- a/src/modules/simulation/simulator_sih/sih.cpp +++ b/src/modules/simulation/simulator_sih/sih.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2019-2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2019-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -75,8 +75,9 @@ void Sih::run() _last_run = task_start; _airspeed_time = task_start; _dist_snsr_time = task_start; - _vehicle = (VehicleType)constrain(_sih_vtype.get(), static_cast(0), - static_cast(3)); + _vehicle = static_cast(constrain(_sih_vtype.get(), + static_cast(VehicleType::First), + static_cast(VehicleType::Last))); _actuator_out_sub = uORB::Subscription{ORB_ID(actuator_outputs_sim)}; @@ -319,7 +320,7 @@ void Sih::read_motors(const float dt) void Sih::generate_force_and_torques() { - if (_vehicle == VehicleType::Multicopter) { + if (_vehicle == VehicleType::Quadcopter) { _T_B = Vector3f(0.0f, 0.0f, -_T_MAX * (+_u[0] + _u[1] + _u[2] + _u[3])); _Mt_B = Vector3f(_L_ROLL * _T_MAX * (-_u[0] + _u[1] + _u[2] - _u[3]), _L_PITCH * _T_MAX * (+_u[0] - _u[1] + _u[2] - _u[3]), @@ -327,6 +328,21 @@ void Sih::generate_force_and_torques() _Fa_E = -_KDV * _v_E; // first order drag to slow down the aircraft _Ma_B = -_KDW * _w_B; // first order angular damper + } else if (_vehicle == VehicleType::Hexacopter) { + /* m5 m0 ┬ + \ / √3/2 + m4 -- + -- m1 ┴ + / \ + m3 m2 + ├1/2┤ + ├ 1 ┤ */ + _T_B = Vector3f(0.0f, 0.0f, -_T_MAX * (+_u[0] + _u[1] + _u[2] + _u[3] + _u[4] + _u[5])); + _Mt_B = Vector3f(_L_ROLL * _T_MAX * (-.5f * _u[0] - _u[1] - .5f * _u[2] + .5f * _u[3] + _u[4] + .5f * _u[5]), + _L_PITCH * _T_MAX * (M_SQRT3_F / 2.f) * (+_u[0] - _u[2] - _u[3] + _u[5]), + _Q_MAX * (+_u[0] - _u[1] + _u[2] - _u[3] + _u[4] - _u[5])); + _Fa_E = -_KDV * _v_E; // first order drag to slow down the aircraft + _Ma_B = -_KDW * _w_B; // first order angular damper + } else if (_vehicle == VehicleType::FixedWing) { _T_B = Vector3f(_T_MAX * _u[3], 0.0f, 0.0f); // forward thruster // _Mt_B = Vector3f(_Q_MAX*_u[3], 0.0f,0.0f); // thruster torque @@ -429,7 +445,8 @@ void Sih::equations_of_motion(const float dt) Vector3f ground_force_E; if ((_lla.altitude() - _lpos_ref_alt) < 0.f && force_down > 0.f) { - if (_vehicle == VehicleType::Multicopter + if (_vehicle == VehicleType::Quadcopter + || _vehicle == VehicleType::Hexacopter || _vehicle == VehicleType::TailsitterVTOL || _vehicle == VehicleType::StandardVTOL) { ground_force_E = -sum_of_forces_E; @@ -715,20 +732,23 @@ int Sih::print_status() PX4_INFO("Achieved speedup: %.2fX", (double)_achieved_speedup); #endif - if (_vehicle == VehicleType::Multicopter) { - PX4_INFO("Running MultiCopter"); + if (_vehicle == VehicleType::Quadcopter) { + PX4_INFO("Quadcopter"); + + } else if (_vehicle == VehicleType::Hexacopter) { + PX4_INFO("Hexacopter"); } else if (_vehicle == VehicleType::FixedWing) { - PX4_INFO("Running Fixed-Wing"); + PX4_INFO("Fixed-Wing"); } else if (_vehicle == VehicleType::TailsitterVTOL) { - PX4_INFO("Running TailSitter"); + PX4_INFO("TailSitter"); PX4_INFO("aoa [deg]: %d", (int)(degrees(_ts[4].get_aoa()))); PX4_INFO("v segment (m/s)"); _ts[4].get_vS().print(); } else if (_vehicle == VehicleType::StandardVTOL) { - PX4_INFO("Running Standard VTOL"); + PX4_INFO("Standard VTOL"); } PX4_INFO("vehicle landed: %d", _grounded); diff --git a/src/modules/simulation/simulator_sih/sih.hpp b/src/modules/simulation/simulator_sih/sih.hpp index 557ec2b16c..4bcc5a281a 100644 --- a/src/modules/simulation/simulator_sih/sih.hpp +++ b/src/modules/simulation/simulator_sih/sih.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * -* Copyright (c) 2019-2022 PX4 Development Team. All rights reserved. +* Copyright (c) 2019-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -218,11 +218,10 @@ private: matrix::Vector3f _v_E_dot{}; matrix::Dcmf _R_N2E; // local navigation to ECEF frame rotation matrix - float _u[NUM_ACTUATORS_MAX] {}; // thruster signals + float _u[NUM_ACTUATORS_MAX] {}; // thruster signals - enum class VehicleType {Multicopter, FixedWing, TailsitterVTOL, StandardVTOL}; - - VehicleType _vehicle = VehicleType::Multicopter; + enum class VehicleType {Quadcopter, FixedWing, TailsitterVTOL, StandardVTOL, Hexacopter, First = Quadcopter, Last = Hexacopter}; // numbering dependent on parameter SIH_VEHICLE_TYPE + VehicleType _vehicle = VehicleType::Quadcopter; // aerodynamic segments for the fixedwing AeroSeg _wing_l = AeroSeg(SPAN / 2.0f, MAC, -4.0f, matrix::Vector3f(0.0f, -SPAN / 4.0f, 0.0f), 3.0f, diff --git a/src/modules/simulation/simulator_sih/sih_params.c b/src/modules/simulation/simulator_sih/sih_params.c index f9e053a5eb..c3112ca598 100644 --- a/src/modules/simulation/simulator_sih/sih_params.c +++ b/src/modules/simulation/simulator_sih/sih_params.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013-2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2013-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,7 +33,7 @@ /** * @file sih_params.c - * Parameters for quadcopter X simulator in hardware. + * Parameters for simulator in hardware. * * @author Romain Chiappinelli * February 2019 @@ -329,10 +329,11 @@ PARAM_DEFINE_FLOAT(SIH_T_TAU, 0.05f); /** * Vehicle type * - * @value 0 Multicopter + * @value 0 Quadcopter * @value 1 Fixed-Wing * @value 2 Tailsitter * @value 3 Standard VTOL + * @value 4 Hexacopter * @reboot_required true * @group Simulation In Hardware */ From 54ddb141373dafeae82d28cee6d2acc955226b31 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 21 May 2025 15:42:05 +1000 Subject: [PATCH 012/130] Update meta docs (#24892) * docs: update module reference metadata * Update failsafe metadata in docs * Update parameter metadata * Fix up uorb graphs based on main * SUMMARY.md - and radio control for modules * Add alternate sidebar --------- Co-authored-by: PX4BuildBot --- docs/en/SUMMARY.md | 1 + docs/en/_sidebar.md | 24 +- .../en/advanced_config/parameter_reference.md | 19 +- docs/en/modules/modules_autotune.md | 13 +- docs/en/modules/modules_command.md | 163 ++++--- docs/en/modules/modules_communication.md | 19 +- docs/en/modules/modules_controller.md | 109 +++-- docs/en/modules/modules_driver.md | 426 +++++++++--------- .../modules/modules_driver_airspeed_sensor.md | 42 +- docs/en/modules/modules_driver_baro.md | 90 ++-- docs/en/modules/modules_driver_camera.md | 6 +- .../modules/modules_driver_distance_sensor.md | 108 +++-- docs/en/modules/modules_driver_imu.md | 204 ++++++--- docs/en/modules/modules_driver_ins.md | 6 +- .../en/modules/modules_driver_magnetometer.md | 84 ++-- .../en/modules/modules_driver_optical_flow.md | 6 +- .../modules/modules_driver_radio_control.md | 126 ++++++ docs/en/modules/modules_driver_rpm_sensor.md | 6 +- docs/en/modules/modules_driver_transponder.md | 6 +- docs/en/modules/modules_estimator.md | 31 +- docs/en/modules/modules_simulation.md | 7 +- docs/en/modules/modules_system.md | 217 ++++++--- docs/en/modules/modules_template.md | 13 +- docs/ko/_sidebar.md | 23 +- docs/public/config/failsafe/index.js | 2 +- docs/public/config/failsafe/index.wasm | Bin 96323 -> 96332 bytes docs/public/config/failsafe/parameters.json | 2 +- docs/public/middleware/graph_full.json | 2 +- .../middleware/graph_full_no_mavlink.json | 2 +- docs/public/middleware/graph_px4_fmu-v2.json | 2 +- docs/public/middleware/graph_px4_fmu-v4.json | 2 +- docs/public/middleware/graph_px4_fmu-v5.json | 2 +- docs/public/middleware/graph_px4_fmu-v5x.json | 1 + docs/public/middleware/graph_px4_fmu-v6x.json | 1 + docs/public/middleware/graph_px4_sitl.json | 2 +- docs/uk/_sidebar.md | 23 +- docs/zh/_sidebar.md | 23 +- 37 files changed, 1185 insertions(+), 628 deletions(-) create mode 100644 docs/en/modules/modules_driver_radio_control.md create mode 100644 docs/public/middleware/graph_px4_fmu-v5x.json create mode 100644 docs/public/middleware/graph_px4_fmu-v6x.json diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index a1bc71b818..79eb11c11a 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -736,6 +736,7 @@ - [Magnetometer](modules/modules_driver_magnetometer.md) - [Optical Flow](modules/modules_driver_optical_flow.md) - [Rpm Sensor](modules/modules_driver_rpm_sensor.md) + - [Radio Control](modules/modules_driver_radio_control.md) - [Transponder](modules/modules_driver_transponder.md) - [Estimators](modules/modules_estimator.md) - [Simulations](modules/modules_simulation.md) diff --git a/docs/en/_sidebar.md b/docs/en/_sidebar.md index 6d5a2976c7..f1629f15d9 100644 --- a/docs/en/_sidebar.md +++ b/docs/en/_sidebar.md @@ -42,8 +42,9 @@ - [MindRacer BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [MindRacer 210](/complete_vehicles_mc/mindracer210.md) - [NanoMind 110](/complete_vehicles_mc/nanomind110.md) - - [Holybro Kopis 2](/complete_vehicles_mc/holybro_kopis2.md) - [Bitcraze Crazyflie 2.1](/complete_vehicles_mc/crazyflie21.md) + - [Holybro Kopis 2](/complete_vehicles_mc/holybro_kopis2.md) + - [Amov F410 Drone](/complete_vehicles_mc/amov_F410_drone.md) - [Kits](/frames_multicopter/kits.md) - [X500 v2 (Pixhawk 6C)](/frames_multicopter/holybro_x500v2_pixhawk6c.md) - [X500 v2 (Pixhawk 5X)](/frames_multicopter/holybro_x500V2_pixhawk5x.md) @@ -166,7 +167,7 @@ - [AirMind MindPX](/flight_controller/mindpx.md) - [AirMind MindRacer](/flight_controller/mindracer.md) - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) - - [ARK FPV Flight Controller](/flight_controller/ark_fpv.md) + - [ARK FPV Flight Controller](/flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](/flight_controller/ark_pi6x.md) - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV Nora](/flight_controller/cuav_nora.md) @@ -182,7 +183,7 @@ - [Holybro Kakute H7v2](/flight_controller/kakuteh7v2.md) - [Holybro Kakute H7mini](/flight_controller/kakuteh7mini.md) - [Holybro Kakute H7](/flight_controller/kakuteh7.md) - - [Holybro Kakute H7 Wing](flight_controller/kakuteh7-wing.md) + - [Holybro Kakute H7 Wing](/flight_controller/kakuteh7-wing.md) - [Holybro Durandal](/flight_controller/durandal.md) - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) @@ -255,7 +256,7 @@ - [GNSS (GPS)](/gps_compass/index.md) - [ARK GPS (CAN)](/dronecan/ark_gps.md) - [ARK SAM GPS](/gps_compass/ark_sam_gps.md) - - [ARK TESEO GPS](/dronecan/ark_teseo_gps.md) + - [ARK TESEO GPS](/dronecan/ark_teseo_gps.md) - [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md) - [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md) - [CUAV NEO 3X GPS (CAN)](/gps_compass/gps_cuav_neo_3x.md) @@ -328,7 +329,9 @@ - [ARK Electron Microhard Serial Telemetry Radio](/telemetry/ark_microhard_serial.md) - [Holybro Microhard P900 Telemetry Radio](/telemetry/holybro_microhard_p900_radio.md) - [CUAV P8 Telemetry Radio](/telemetry/cuav_p8_radio.md) + - [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md) - [HolyBro XBP9X - Discontinued](/telemetry/holybro_xbp9x_radio.md) + - [FrSky Telemetry](/peripherals/frsky_telemetry.md) - [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md) - [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) @@ -713,6 +716,10 @@ - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](/middleware/mavlink.md) + - [Adding Messages](/mavlink/adding_messages.md) + - [Streaming Messages](/mavlink/streaming_messages.md) + - [Receiving Messages](/mavlink/receiving_messages.md) + - [Custom MAVLink Messages](/mavlink/custom_messages.md) - [Standard Modes Protocol](/mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md) - [Modules & Commands](/modules/modules_main.md) @@ -730,6 +737,7 @@ - [Magnetometer](/modules/modules_driver_magnetometer.md) - [Optical Flow](/modules/modules_driver_optical_flow.md) - [Rpm Sensor](/modules/modules_driver_rpm_sensor.md) + - [Radio Control](/modules/modules_driver_radio_control.md) - [Transponder](/modules/modules_driver_transponder.md) - [Estimators](/modules/modules_estimator.md) - [Simulations](/modules/modules_simulation.md) @@ -801,8 +809,10 @@ - [Test MC_05 - Indoor Flight (Manual Modes)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [Unit Tests](/test_and_ci/unit_tests.md) - [Continuous Integration](/test_and_ci/continous_integration.md) - - [MAVSDK Integration Testing](/test_and_ci/integration_testing_mavsdk.md) - - [ROS Integration Testing](/test_and_ci/integration_testing.md) + - [Integration Testing](/test_and_ci/integration_testing.md) + - [MAVSDK Integration Testing](/test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](/test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](/test_and_ci/integration_testing_ros1_mavros.md) - [Docker Containers](/test_and_ci/docker.md) - [Maintenance](/test_and_ci/maintenance.md) - [Drone Apps & APIs](/robotics/index.md) @@ -840,4 +850,4 @@ - [1.15 (stable)](/releases/1.15.md) - [1.14](/releases/1.14.md) - [1.13](/releases/1.13.md) - - [1.12](/releases/1.12.md) \ No newline at end of file + - [1.12](/releases/1.12.md) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index c0fedadfc9..bb538fd661 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -30755,7 +30755,7 @@ INA226 Power Monitor Config. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0 | 65535 | 1 | 18139 | +✓ | 0 | 65535 | 1 | 18139 | ### INA226_CURRENT (`FLOAT`) {#INA226_CURRENT} @@ -30763,7 +30763,7 @@ INA226 Power Monitor Max Current. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.1 | 200.0 | 0.1 | 164.0 | +✓ | 0.1 | 200.0 | 0.1 | 164.0 | ### INA226_SHUNT (`FLOAT`) {#INA226_SHUNT} @@ -30771,7 +30771,7 @@ INA226 Power Monitor Shunt. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.000000001 | 0.1 | .000000001 | 0.0005 | +✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | ### INA228_CONFIG (`INT32`) {#INA228_CONFIG} @@ -30779,7 +30779,7 @@ INA228 Power Monitor Config. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0 | 65535 | 1 | 63779 | +✓ | 0 | 65535 | 1 | 63779 | ### INA228_CURRENT (`FLOAT`) {#INA228_CURRENT} @@ -30787,7 +30787,7 @@ INA228 Power Monitor Max Current. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.1 | 327.68 | 0.1 | 327.68 | +✓ | 0.1 | 327.68 | 0.1 | 327.68 | ### INA228_SHUNT (`FLOAT`) {#INA228_SHUNT} @@ -30795,7 +30795,7 @@ INA228 Power Monitor Shunt. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.000000001 | 0.1 | .000000001 | 0.0005 | +✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | ### INA238_CURRENT (`FLOAT`) {#INA238_CURRENT} @@ -30803,7 +30803,7 @@ INA238 Power Monitor Max Current. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.1 | 327.68 | 0.1 | 327.68 | +✓ | 0.1 | 327.68 | 0.1 | 327.68 | ### INA238_SHUNT (`FLOAT`) {#INA238_SHUNT} @@ -30811,7 +30811,7 @@ INA238 Power Monitor Shunt. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.000000001 | 0.1 | .000000001 | 0.0003 | +✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | ### PCF8583_MAGNET (`INT32`) {#PCF8583_MAGNET} @@ -33642,10 +33642,11 @@ Vehicle type. **Values:** -- `0`: Multicopter +- `0`: Quadcopter - `1`: Fixed-Wing - `2`: Tailsitter - `3`: Standard VTOL +- `4`: Hexacopter Reboot | minValue | maxValue | increment | default | unit diff --git a/docs/en/modules/modules_autotune.md b/docs/en/modules/modules_autotune.md index 69df6b4280..2292dd7494 100644 --- a/docs/en/modules/modules_autotune.md +++ b/docs/en/modules/modules_autotune.md @@ -1,14 +1,17 @@ # Modules Reference: Autotune + + ## fw_autotune_attitude_control + Source: [modules/fw_autotune_attitude_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_autotune_attitude_control) ### Description - -### Usage +### Usage {#fw_autotune_attitude_control_usage} + ``` fw_autotune_attitude_control [arguments...] Commands: @@ -19,15 +22,17 @@ fw_autotune_attitude_control [arguments...] status print status info ``` + ## mc_autotune_attitude_control + Source: [modules/mc_autotune_attitude_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_autotune_attitude_control) ### Description - -### Usage +### Usage {#mc_autotune_attitude_control_usage} + ``` mc_autotune_attitude_control [arguments...] Commands: diff --git a/docs/en/modules/modules_command.md b/docs/en/modules/modules_command.md index 4a37e7e5c5..4bba93f042 100644 --- a/docs/en/modules/modules_command.md +++ b/docs/en/modules/modules_command.md @@ -1,6 +1,9 @@ # Modules Reference: Command + + ## actuator_test + Source: [systemcmds/actuator_test](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/actuator_test) @@ -8,8 +11,8 @@ Utility to test actuators. WARNING: remove all props before using this command. - -### Usage +### Usage {#actuator_test_usage} + ``` actuator_test [arguments...] Commands: @@ -27,12 +30,14 @@ actuator_test [arguments...] iterate-servos Iterate all servos deflecting one after the other ``` + ## bl_update + Source: [systemcmds/bl_update](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bl_update) Utility to flash the bootloader from a file - -### Usage +### Usage {#bl_update_usage} + ``` bl_update [arguments...] setopt Set option bits to unlock the FLASH (only needed if in locked @@ -40,27 +45,33 @@ bl_update [arguments...] Bootloader bin file ``` + ## bsondump + Source: [systemcmds/bsondump](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bsondump) Utility to read BSON from a file and print or output document size. - -### Usage +### Usage {#bsondump_usage} + ``` bsondump [arguments...] The BSON file to decode and print. ``` + ## dumpfile + Source: [systemcmds/dumpfile](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dumpfile) Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. - -### Usage +### Usage {#dumpfile_usage} + ``` dumpfile [arguments...] File to dump ``` + ## dyn + Source: [systemcmds/dyn](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dyn) @@ -73,14 +84,16 @@ dyn ./hello.px4mod start ``` - -### Usage +### Usage {#dyn_usage} + ``` dyn [arguments...] File containing the module [arguments...] Arguments to the module ``` + ## failure + Source: [systemcmds/failure](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/failure) @@ -95,8 +108,8 @@ Test the GPS failsafe by stopping GPS: failure gps off - -### Usage +### Usage {#failure_usage} + ``` failure [arguments...] help Show this help text @@ -107,7 +120,9 @@ failure [arguments...] [-i ] sensor instance (0=all) default: 0 ``` + ## gpio + Source: [systemcmds/gpio](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/gpio) @@ -136,8 +151,8 @@ gpio write /dev/gpio1 1 ``` - -### Usage +### Usage {#gpio_usage} + ``` gpio [arguments...] read @@ -151,15 +166,17 @@ gpio [arguments...] [PUSHPULL|OPENDRAIN] Pushpull/Opendrain [--force] Force (ignore board gpio list) ``` + ## hardfault_log + Source: [systemcmds/hardfault_log](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hardfault_log) Hardfault utility Used in startup scripts to handle hardfaults - -### Usage +### Usage {#hardfault_log_usage} + ``` hardfault_log [arguments...] Commands: @@ -180,27 +197,33 @@ hardfault_log [arguments...] reset Reset the reboot counter ``` + ## hist + Source: [systemcmds/hist](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hist) Command-line tool to show the px4 message history. There are no arguments. - -### Usage +### Usage {#hist_usage} + ``` hist [arguments...] ``` + ## i2cdetect + Source: [systemcmds/i2cdetect](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/i2cdetect) Utility to scan for I2C devices on a particular bus. - -### Usage +### Usage {#i2cdetect_usage} + ``` i2cdetect [arguments...] [-b ] I2C bus default: 1 ``` + ## led_control + Source: [systemcmds/led_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/led_control) @@ -220,8 +243,8 @@ led_control blink -c blue -l 0 -n 5 ``` - -### Usage +### Usage {#led_control_usage} + ``` led_control [arguments...] Commands: @@ -251,7 +274,9 @@ led_control [arguments...] [-p ] Priority default: 2 ``` + ## listener + Source: [systemcmds/topic_listener](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/topic_listener) @@ -259,8 +284,8 @@ Utility to listen on uORB topics and print the data to the console. The listener can be exited any time by pressing Ctrl+C, Esc, or Q. - -### Usage +### Usage {#listener_usage} + ``` listener [arguments...] Commands: @@ -272,23 +297,27 @@ listener [arguments...] [-r ] Subscription rate (unlimited if 0) default: 0 ``` + ## mfd + Source: [systemcmds/mft](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft) Utility interact with the manifest - -### Usage +### Usage {#mfd_usage} + ``` mfd [arguments...] Commands: query Returns true if not existed ``` + ## mft_cfg + Source: [systemcmds/mft_cfg](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft_cfg) Tool to set and get manifest configuration - -### Usage +### Usage {#mft_cfg_usage} + ``` mft_cfg [arguments...] Commands: @@ -301,12 +330,14 @@ mft_cfg [arguments...] -i argument to set extended hardware id (id == version for , id == revision for ) ``` + ## mtd + Source: [systemcmds/mtd](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mtd) Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) - -### Usage +### Usage {#mtd_usage} + ``` mtd [arguments...] Commands: @@ -326,7 +357,9 @@ mtd [arguments...] [ [ ...]] Partition names (eg. /fs/mtd_params), use system default if not provided ``` + ## nshterm + Source: [systemcmds/nshterm](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/nshterm) Start an NSH shell on a given port. @@ -334,13 +367,15 @@ Start an NSH shell on a given port. This was previously used to start a shell on the USB serial port. Now there runs mavlink, and it is possible to use a shell over mavlink. - -### Usage +### Usage {#nshterm_usage} + ``` nshterm [arguments...] Device on which to start the shell (eg. /dev/ttyACM0) ``` + ## param + Source: [systemcmds/param](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/param) @@ -368,8 +403,8 @@ param set SYS_AUTOCONFIG 1 reboot ``` - -### Usage +### Usage {#param_usage} + ``` param [arguments...] Commands: @@ -436,7 +471,9 @@ param [arguments...] find Show index of a param param name ``` + ## payload_deliverer + Source: [modules/payload_deliverer](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/payload_deliverer) @@ -445,8 +482,8 @@ Handles payload delivery with either Gripper or a Winch with an appropriate time and communicates back the delivery result as an acknowledgement internally - -### Usage +### Usage {#payload_deliverer_usage} + ``` payload_deliverer [arguments...] Commands: @@ -462,12 +499,14 @@ payload_deliverer [arguments...] status print status info ``` + ## perf + Source: [systemcmds/perf](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/perf) Tool to print performance counters - -### Usage +### Usage {#perf_usage} + ``` perf [arguments...] reset Reset all counters @@ -476,24 +515,28 @@ perf [arguments...] Prints all performance counters if no arguments given ``` + ## reboot + Source: [systemcmds/reboot](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/reboot) Reboot the system - -### Usage +### Usage {#reboot_usage} + ``` reboot [arguments...] [-b] Reboot into bootloader [-i] Reboot into ISP (1st stage bootloader) [lock|unlock] Take/release the shutdown lock (for testing) ``` + ## sd_bench + Source: [systemcmds/sd_bench](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_bench) Test the speed of an SD Card - -### Usage +### Usage {#sd_bench_usage} + ``` sd_bench [arguments...] [-b ] Block size for each read/write @@ -508,12 +551,14 @@ sd_bench [arguments...] [-U] Test performance with forced byte unaligned data [-v] Verify data and block number ``` + ## sd_stress + Source: [systemcmds/sd_stress](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_stress) Test operations on an SD Card - -### Usage +### Usage {#sd_stress_usage} + ``` sd_stress [arguments...] [-r ] Number of runs @@ -521,15 +566,17 @@ sd_stress [arguments...] [-b ] Number of bytes default: 100 ``` + ## serial_passthru + Source: [systemcmds/serial_passthru](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/serial_passthru) Pass data from one device to another. This can be used to use u-center connected to USB with a GPS on a serial port. - -### Usage +### Usage {#serial_passthru_usage} + ``` serial_passthru [arguments...] -e External device path @@ -540,7 +587,9 @@ serial_passthru [arguments...] default: 115200 [-t] Track the External devices baudrate on internal device ``` + ## system_time + Source: [systemcmds/system_time](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/system_time) @@ -556,8 +605,8 @@ system_time set 1600775044 system_time get ``` - -### Usage +### Usage {#system_time_usage} + ``` system_time [arguments...] Commands: @@ -565,32 +614,38 @@ system_time [arguments...] get Get the system time ``` + ## top + Source: [systemcmds/top](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/top) Monitor running processes and their CPU, stack usage, priority and state - -### Usage +### Usage {#top_usage} + ``` top [arguments...] once print load only once ``` + ## usb_connected + Source: [systemcmds/usb_connected](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/usb_connected) Utility to check if USB is connected. Was previously used in startup scripts. A return value of 0 means USB is connected, 1 otherwise. - -### Usage +### Usage {#usb_connected_usage} + ``` usb_connected [arguments...] ``` + ## ver + Source: [systemcmds/ver](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/ver) Tool to print various version information - -### Usage +### Usage {#ver_usage} + ``` ver [arguments...] Commands: diff --git a/docs/en/modules/modules_communication.md b/docs/en/modules/modules_communication.md index 45670a0018..840e9af3be 100644 --- a/docs/en/modules/modules_communication.md +++ b/docs/en/modules/modules_communication.md @@ -1,11 +1,14 @@ # Modules Reference: Communication + + ## frsky_telemetry + Source: [drivers/telemetry/frsky_telemetry](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/frsky_telemetry) FrSky Telemetry support. Auto-detects D or S.PORT protocol. - -### Usage +### Usage {#frsky_telemetry_usage} + ``` frsky_telemetry [arguments...] Commands: @@ -22,7 +25,9 @@ frsky_telemetry [arguments...] status ``` + ## mavlink + Source: [modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink) @@ -57,8 +62,8 @@ mavlink start -u 14556 -r 1000000 mavlink stream -u 14556 -s HIGHRES_IMU -r 50 ``` - -### Usage +### Usage {#mavlink_usage} + ``` mavlink [arguments...] Commands: @@ -113,7 +118,9 @@ mavlink [arguments...] boot_complete Enable sending of messages. (Must be) called as last step in startup script. ``` + ## uorb + Source: [systemcmds/uorb](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/uorb) @@ -137,8 +144,8 @@ Monitor topic publication rates. Besides `top`, this is an important command for uorb top ``` - -### Usage +### Usage {#uorb_usage} + ``` uorb [arguments...] Commands: diff --git a/docs/en/modules/modules_controller.md b/docs/en/modules/modules_controller.md index 580bb33b11..e09206b296 100644 --- a/docs/en/modules/modules_controller.md +++ b/docs/en/modules/modules_controller.md @@ -1,6 +1,9 @@ # Modules Reference: Controller + + ## airship_att_control + Source: [modules/airship_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/airship_att_control) @@ -15,8 +18,8 @@ Currently it is feeding the `manual_control_setpoint` topic directly to the actu To reduce control latency, the module directly polls on the gyro topic published by the IMU driver. - -### Usage +### Usage {#airship_att_control_usage} + ``` airship_att_control [arguments...] Commands: @@ -26,7 +29,9 @@ airship_att_control [arguments...] status print status info ``` + ## control_allocator + Source: [modules/control_allocator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/control_allocator) @@ -34,8 +39,8 @@ Source: [modules/control_allocator](https://github.com/PX4/PX4-Autopilot/tree/ma This implements control allocation. It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages. - -### Usage +### Usage {#control_allocator_usage} + ``` control_allocator [arguments...] Commands: @@ -45,7 +50,9 @@ control_allocator [arguments...] status print status info ``` + ## flight_mode_manager + Source: [modules/flight_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/flight_mode_manager) @@ -54,8 +61,8 @@ This implements the setpoint generation for all modes. It takes the current mode and outputs setpoints for controllers. - -### Usage +### Usage {#flight_mode_manager_usage} + ``` flight_mode_manager [arguments...] Commands: @@ -65,7 +72,9 @@ flight_mode_manager [arguments...] status print status info ``` + ## fw_att_control + Source: [modules/fw_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_att_control) @@ -73,8 +82,8 @@ Source: [modules/fw_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/ fw_att_control is the fixed wing attitude controller. - -### Usage +### Usage {#fw_att_control_usage} + ``` fw_att_control [arguments...] Commands: @@ -85,7 +94,9 @@ fw_att_control [arguments...] status print status info ``` + ## fw_pos_control + Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_pos_control) @@ -93,8 +104,8 @@ Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/ fw_pos_control is the fixed-wing position controller. - -### Usage +### Usage {#fw_pos_control_usage} + ``` fw_pos_control [arguments...] Commands: @@ -105,7 +116,9 @@ fw_pos_control [arguments...] status print status info ``` + ## fw_rate_control + Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_rate_control) @@ -113,8 +126,8 @@ Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main fw_rate_control is the fixed-wing rate controller. - -### Usage +### Usage {#fw_rate_control_usage} + ``` fw_rate_control [arguments...] Commands: @@ -125,7 +138,9 @@ fw_rate_control [arguments...] status print status info ``` + ## mc_att_control + Source: [modules/mc_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_att_control) @@ -143,8 +158,8 @@ Institute for Dynamic Systems and Control (IDSC), ETH Zurich https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf - -### Usage +### Usage {#mc_att_control_usage} + ``` mc_att_control [arguments...] Commands: @@ -155,7 +170,9 @@ mc_att_control [arguments...] status print status info ``` + ## mc_pos_control + Source: [modules/mc_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_pos_control) @@ -167,8 +184,8 @@ Output of the velocity controller is thrust vector that is split to thrust direc The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and logging. - -### Usage +### Usage {#mc_pos_control_usage} + ``` mc_pos_control [arguments...] Commands: @@ -179,7 +196,9 @@ mc_pos_control [arguments...] status print status info ``` + ## mc_rate_control + Source: [modules/mc_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_rate_control) @@ -190,8 +209,8 @@ via `manual_control_setpoint` topic) as inputs and outputs actuator control mess The controller has a PID loop for angular rate error. - -### Usage +### Usage {#mc_rate_control_usage} + ``` mc_rate_control [arguments...] Commands: @@ -202,7 +221,9 @@ mc_rate_control [arguments...] status print status info ``` + ## navigator + Source: [modules/navigator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/navigator) @@ -219,8 +240,8 @@ Navigator publishes position setpoint triplets (`position_setpoint_triplet_s`), controller. - -### Usage +### Usage {#navigator_usage} + ``` navigator [arguments...] Commands: @@ -234,15 +255,17 @@ navigator [arguments...] status print status info ``` + ## rover_ackermann + Source: [modules/rover_ackermann](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/rover_ackermann) ### Description Rover ackermann module. - -### Usage +### Usage {#rover_ackermann_usage} + ``` rover_ackermann [arguments...] Commands: @@ -252,15 +275,17 @@ rover_ackermann [arguments...] status print status info ``` + ## rover_differential + Source: [modules/rover_differential](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/rover_differential) ### Description Rover differential module. - -### Usage +### Usage {#rover_differential_usage} + ``` rover_differential [arguments...] Commands: @@ -270,15 +295,17 @@ rover_differential [arguments...] status print status info ``` + ## rover_mecanum + Source: [modules/rover_mecanum](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/rover_mecanum) ### Description Rover mecanum module. - -### Usage +### Usage {#rover_mecanum_usage} + ``` rover_mecanum [arguments...] Commands: @@ -288,7 +315,9 @@ rover_mecanum [arguments...] status print status info ``` + ## rover_pos_control + Source: [modules/rover_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/rover_pos_control) @@ -313,8 +342,8 @@ rover_pos_control stop ``` - -### Usage +### Usage {#rover_pos_control_usage} + ``` rover_pos_control [arguments...] Commands: @@ -324,7 +353,9 @@ rover_pos_control [arguments...] status print status info ``` + ## spacecraft + Source: [modules/spacecraft](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/spacecraft) @@ -333,8 +364,8 @@ Source: [modules/spacecraft](https://github.com/PX4/PX4-Autopilot/tree/main/src/ It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages. - -### Usage +### Usage {#spacecraft_usage} + ``` spacecraft [arguments...] Commands: @@ -344,7 +375,9 @@ spacecraft [arguments...] status print status info ``` + ## uuv_att_control + Source: [modules/uuv_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/uuv_att_control) @@ -368,8 +401,8 @@ uuv_att_control stop ``` - -### Usage +### Usage {#uuv_att_control_usage} + ``` uuv_att_control [arguments...] Commands: @@ -379,7 +412,9 @@ uuv_att_control [arguments...] status print status info ``` + ## uuv_pos_control + Source: [modules/uuv_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/uuv_pos_control) @@ -398,8 +433,8 @@ uuv_pos_control status uuv_pos_control stop ``` - -### Usage +### Usage {#uuv_pos_control_usage} + ``` uuv_pos_control [arguments...] Commands: @@ -409,15 +444,17 @@ uuv_pos_control [arguments...] status print status info ``` + ## vtol_att_control + Source: [modules/vtol_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/vtol_att_control) ### Description fw_att_control is the fixed wing attitude controller. - -### Usage +### Usage {#vtol_att_control_usage} + ``` vtol_att_control [arguments...] Commands: diff --git a/docs/en/modules/modules_driver.md b/docs/en/modules/modules_driver.md index f41731b0f2..3c5f1966ff 100644 --- a/docs/en/modules/modules_driver.md +++ b/docs/en/modules/modules_driver.md @@ -1,21 +1,26 @@ # Modules Reference: Driver + Subcategories: + - [Airspeed Sensor](modules_driver_airspeed_sensor.md) -- [Transponder](modules_driver_transponder.md) -- [Imu](modules_driver_imu.md) -- [Rpm Sensor](modules_driver_rpm_sensor.md) -- [Magnetometer](modules_driver_magnetometer.md) +- [Baro](modules_driver_baro.md) - [Camera](modules_driver_camera.md) - [Distance Sensor](modules_driver_distance_sensor.md) -- [Optical Flow](modules_driver_optical_flow.md) +- [Imu](modules_driver_imu.md) - [Ins](modules_driver_ins.md) -- [Baro](modules_driver_baro.md) +- [Magnetometer](modules_driver_magnetometer.md) +- [Optical Flow](modules_driver_optical_flow.md) +- [Radio Control](modules_driver_radio_control.md) +- [Rpm Sensor](modules_driver_rpm_sensor.md) +- [Transponder](modules_driver_transponder.md) + ## MCP23009 + Source: [drivers/gpio/mcp23009](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gpio/mcp23009) - -### Usage +### Usage {#MCP23009_usage} + ``` MCP23009 [arguments...] Commands: @@ -41,7 +46,9 @@ MCP23009 [arguments...] status print status info ``` + ## adc + Source: [drivers/adc/board_adc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/board_adc) @@ -49,8 +56,8 @@ Source: [drivers/adc/board_adc](https://github.com/PX4/PX4-Autopilot/tree/main/s ADC driver. - -### Usage +### Usage {#adc_usage} + ``` adc [arguments...] Commands: @@ -63,7 +70,9 @@ adc [arguments...] status print status info ``` + ## ads1115 + Source: [drivers/adc/ads1115](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/ads1115) @@ -81,8 +90,8 @@ parameter, and is disabled by default. If enabled, internal ADCs are not used. - -### Usage +### Usage {#ads1115_usage} + ``` ads1115 [arguments...] Commands: @@ -100,7 +109,9 @@ ads1115 [arguments...] status print status info ``` + ## atxxxx + Source: [drivers/osd/atxxxx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/osd/atxxxx) @@ -109,8 +120,8 @@ OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for exam It can be enabled with the OSD_ATXXXX_CFG parameter. - -### Usage +### Usage {#atxxxx_usage} + ``` atxxxx [arguments...] Commands: @@ -128,7 +139,9 @@ atxxxx [arguments...] status print status info ``` + ## batmon + Source: [drivers/smart_battery/batmon](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/smart_battery/batmon) @@ -142,8 +155,8 @@ batmon start -X -a 11 -b 4 ``` - -### Usage +### Usage {#batmon_usage} + ``` batmon [arguments...] Commands: @@ -167,7 +180,9 @@ batmon [arguments...] status print status info ``` + ## batt_smbus + Source: [drivers/batt_smbus](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/batt_smbus) @@ -181,8 +196,8 @@ batt_smbus -X write_flash 19069 2 27 0 ``` - -### Usage +### Usage {#batt_smbus_usage} + ``` batt_smbus [arguments...] Commands: @@ -217,11 +232,13 @@ batt_smbus [arguments...] status print status info ``` + ## bst + Source: [drivers/telemetry/bst](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/bst) - -### Usage +### Usage {#bst_usage} + ``` bst [arguments...] Commands: @@ -239,28 +256,9 @@ bst [arguments...] status print status info ``` -## crsf_rc -Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) - -### Description -This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data - - - -### Usage -``` -crsf_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` ## dshot + Source: [drivers/dshot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/dshot) @@ -284,8 +282,8 @@ dshot save -m 1 ``` After saving, the reversed direction will be regarded as the normal one. So to reverse again repeat the same commands. - -### Usage +### Usage {#dshot_usage} + ``` dshot [arguments...] Commands: @@ -331,38 +329,17 @@ dshot [arguments...] status print status info ``` -## dsm_rc -Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) - -### Description -This module does Spektrum DSM RC input parsing. - - - -### Usage -``` -dsm_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` ## fake_gps + Source: [examples/fake_gps](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/fake_gps) ### Description - -### Usage +### Usage {#fake_gps_usage} + ``` fake_gps [arguments...] Commands: @@ -372,15 +349,17 @@ fake_gps [arguments...] status print status info ``` + ## fake_imu + Source: [examples/fake_imu](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/fake_imu) ### Description - -### Usage +### Usage {#fake_imu_usage} + ``` fake_imu [arguments...] Commands: @@ -390,7 +369,9 @@ fake_imu [arguments...] status print status info ``` + ## fake_magnetometer + Source: [examples/fake_magnetometer](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/fake_magnetometer) @@ -398,8 +379,8 @@ Source: [examples/fake_magnetometer](https://github.com/PX4/PX4-Autopilot/tree/m Publish the earth magnetic field as a fake magnetometer (sensor_mag). Requires vehicle_attitude and vehicle_gps_position. - -### Usage +### Usage {#fake_magnetometer_usage} + ``` fake_magnetometer [arguments...] Commands: @@ -409,7 +390,9 @@ fake_magnetometer [arguments...] status print status info ``` + ## ft_technologies_serial + Source: [drivers/wind_sensor/ft_technologies](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/wind_sensor/ft_technologies) @@ -431,8 +414,8 @@ Stop driver ft_technologies_serial stop ``` - -### Usage +### Usage {#ft_technologies_serial_usage} + ``` ft_technologies_serial [arguments...] Commands: @@ -441,28 +424,9 @@ ft_technologies_serial [arguments...] stop Stop driver ``` -## ghst_rc -Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) - -### Description -This module does Ghost (GHST) RC input parsing. - - - -### Usage -``` -ghst_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` ## gimbal + Source: [modules/gimbal](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/gimbal) @@ -478,8 +442,8 @@ Test the output by setting a angles (all omitted axes are set to 0): gimbal test pitch -45 yaw 30 ``` - -### Usage +### Usage {#gimbal_usage} + ``` gimbal [arguments...] Commands: @@ -500,7 +464,9 @@ gimbal [arguments...] status print status info ``` + ## gps + Source: [drivers/gps](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gps) @@ -528,8 +494,8 @@ Initiate warm restart of GPS device gps reset warm ``` - -### Usage +### Usage {#gps_usage} + ``` gps [arguments...] Commands: @@ -556,15 +522,17 @@ gps [arguments...] reset Reset GPS device cold|warm|hot Specify reset type ``` + ## gz_bridge + Source: [modules/simulation/gz_bridge](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_bridge) ### Description - -### Usage +### Usage {#gz_bridge_usage} + ``` gz_bridge [arguments...] Commands: @@ -576,7 +544,9 @@ gz_bridge [arguments...] status print status info ``` + ## ina220 + Source: [drivers/power_monitor/ina220](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/ina220) @@ -593,8 +563,8 @@ every 0.5 seconds. With this flag set, you can plug in a battery after the drive this flag set, the battery must be plugged in before starting the driver. - -### Usage +### Usage {#ina220_usage} + ``` ina220 [arguments...] Commands: @@ -617,7 +587,9 @@ ina220 [arguments...] status print status info ``` + ## ina226 + Source: [drivers/power_monitor/ina226](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/ina226) @@ -634,8 +606,8 @@ every 0.5 seconds. With this flag set, you can plug in a battery after the drive this flag set, the battery must be plugged in before starting the driver. - -### Usage +### Usage {#ina226_usage} + ``` ina226 [arguments...] Commands: @@ -656,7 +628,9 @@ ina226 [arguments...] status print status info ``` + ## ina228 + Source: [drivers/power_monitor/ina228](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/ina228) @@ -673,8 +647,8 @@ every 0.5 seconds. With this flag set, you can plug in a battery after the drive this flag set, the battery must be plugged in before starting the driver. - -### Usage +### Usage {#ina228_usage} + ``` ina228 [arguments...] Commands: @@ -695,7 +669,9 @@ ina228 [arguments...] status print status info ``` + ## ina238 + Source: [drivers/power_monitor/ina238](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/ina238) @@ -712,8 +688,8 @@ every 0.5 seconds. With this flag set, you can plug in a battery after the drive this flag set, the battery must be plugged in before starting the driver. - -### Usage +### Usage {#ina238_usage} + ``` ina238 [arguments...] Commands: @@ -734,7 +710,9 @@ ina238 [arguments...] status print status info ``` + ## iridiumsbd + Source: [drivers/telemetry/iridiumsbd](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/iridiumsbd) @@ -743,8 +721,8 @@ IridiumSBD driver. Creates a virtual serial port that another module can use for communication (e.g. mavlink). - -### Usage +### Usage {#iridiumsbd_usage} + ``` iridiumsbd [arguments...] Commands: @@ -760,11 +738,13 @@ iridiumsbd [arguments...] status print status info ``` + ## irlock + Source: [drivers/irlock](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/irlock) - -### Usage +### Usage {#irlock_usage} + ``` irlock [arguments...] Commands: @@ -782,15 +762,17 @@ irlock [arguments...] status print status info ``` + ## linux_pwm_out + Source: [drivers/linux_pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/linux_pwm_out) ### Description Linux PWM output driver with board-specific backend implementation. - -### Usage +### Usage {#linux_pwm_out_usage} + ``` linux_pwm_out [arguments...] Commands: @@ -800,11 +782,13 @@ linux_pwm_out [arguments...] status print status info ``` + ## lsm303agr + Source: [drivers/magnetometer/lsm303agr](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm303agr) - -### Usage +### Usage {#lsm303agr_usage} + ``` lsm303agr [arguments...] Commands: @@ -824,7 +808,9 @@ lsm303agr [arguments...] status print status info ``` + ## msp_osd + Source: [drivers/osd/msp_osd](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/osd/msp_osd) @@ -841,8 +827,8 @@ msp_osd ``` - -### Usage +### Usage {#msp_osd_usage} + ``` msp_osd [arguments...] Commands: @@ -850,7 +836,9 @@ msp_osd [arguments...] status print status info ``` + ## newpixel + Source: [drivers/lights/neopixel](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/neopixel) @@ -864,8 +852,8 @@ neopixel -n 8 ``` To drive all available leds. - -### Usage +### Usage {#newpixel_usage} + ``` newpixel [arguments...] Commands: @@ -873,11 +861,13 @@ newpixel [arguments...] status print status info ``` + ## paa3905 + Source: [drivers/optical_flow/paa3905](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paa3905) - -### Usage +### Usage {#paa3905_usage} + ``` paa3905 [arguments...] Commands: @@ -897,11 +887,13 @@ paa3905 [arguments...] status print status info ``` + ## paw3902 + Source: [drivers/optical_flow/paw3902](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paw3902) - -### Usage +### Usage {#paw3902_usage} + ``` paw3902 [arguments...] Commands: @@ -921,7 +913,9 @@ paw3902 [arguments...] status print status info ``` + ## pca9685_pwm_out + Source: [drivers/pca9685_pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/pca9685_pwm_out) @@ -941,8 +935,8 @@ pca9685_pwm_out start -a 0x40 -b 1 ``` - -### Usage +### Usage {#pca9685_pwm_out_usage} + ``` pca9685_pwm_out [arguments...] Commands: @@ -956,7 +950,9 @@ pca9685_pwm_out [arguments...] status print status info ``` + ## pm_selector_auterion + Source: [drivers/power_monitor/pm_selector_auterion](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/pm_selector_auterion) @@ -964,8 +960,8 @@ Source: [drivers/power_monitor/pm_selector_auterion](https://github.com/PX4/PX4- Driver for starting and auto-detecting different power monitors. - -### Usage +### Usage {#pm_selector_auterion_usage} + ``` pm_selector_auterion [arguments...] Commands: @@ -975,11 +971,13 @@ pm_selector_auterion [arguments...] status print status info ``` + ## pmw3901 + Source: [drivers/optical_flow/pmw3901](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/pmw3901) - -### Usage +### Usage {#pmw3901_usage} + ``` pmw3901 [arguments...] Commands: @@ -999,7 +997,9 @@ pmw3901 [arguments...] status print status info ``` + ## pps_capture + Source: [drivers/pps_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/pps_capture) @@ -1007,8 +1007,8 @@ Source: [drivers/pps_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src This implements capturing PPS information from the GNSS module and calculates the drift between PPS and Real-time clock. - -### Usage +### Usage {#pps_capture_usage} + ``` pps_capture [arguments...] Commands: @@ -1018,7 +1018,9 @@ pps_capture [arguments...] status print status info ``` + ## pwm_out + Source: [drivers/pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/pwm_out) @@ -1028,8 +1030,8 @@ This module is responsible for driving the output pins. For boards without a sep px4io driver is used for main ones. - -### Usage +### Usage {#pwm_out_usage} + ``` pwm_out [arguments...] Commands: @@ -1039,7 +1041,9 @@ pwm_out [arguments...] status print status info ``` + ## pwm_out_sim + Source: [modules/simulation/pwm_out_sim](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/pwm_out_sim) @@ -1053,8 +1057,8 @@ mix them with any loaded mixer and output the result to the It is used in SITL and HITL. - -### Usage +### Usage {#pwm_out_sim_usage} + ``` pwm_out_sim [arguments...] Commands: @@ -1066,11 +1070,13 @@ pwm_out_sim [arguments...] status print status info ``` + ## px4flow + Source: [drivers/optical_flow/px4flow](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/px4flow) - -### Usage +### Usage {#px4flow_usage} + ``` px4flow [arguments...] Commands: @@ -1088,15 +1094,17 @@ px4flow [arguments...] status print status info ``` + ## px4io + Source: [drivers/px4io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/px4io) ### Description Output driver communicating with the IO co-processor. - -### Usage +### Usage {#px4io_usage} + ``` px4io [arguments...] Commands: @@ -1128,40 +1136,13 @@ px4io [arguments...] status print status info ``` -## rc_input -Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) - -### Description -This module does the RC input parsing and auto-selecting the method. Supported methods are: -- PPM -- SBUS -- DSM -- SUMD -- ST24 -- TBS Crossfire (CRSF) - - - -### Usage -``` -rc_input [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` ## rgbled + Source: [drivers/lights/rgbled_ncp5623c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_ncp5623c) - -### Usage +### Usage {#rgbled_usage} + ``` rgbled [arguments...] Commands: @@ -1181,11 +1162,13 @@ rgbled [arguments...] status print status info ``` + ## rgbled_is31fl3195 + Source: [drivers/lights/rgbled_is31fl3195](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_is31fl3195) - -### Usage +### Usage {#rgbled_is31fl3195_usage} + ``` rgbled_is31fl3195 [arguments...] Commands: @@ -1207,7 +1190,9 @@ rgbled_is31fl3195 [arguments...] status print status info ``` + ## rgbled_lp5562 + Source: [drivers/lights/rgbled_lp5562](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_lp5562) @@ -1218,8 +1203,8 @@ This used in some GPS modules by Holybro for [PX4 status notification](../gettin The driver is included by default in firmware (KConfig key DRIVERS_LIGHTS_RGBLED_LP5562) and is always enabled. - -### Usage +### Usage {#rgbled_lp5562_usage} + ``` rgbled_lp5562 [arguments...] Commands: @@ -1239,7 +1224,9 @@ rgbled_lp5562 [arguments...] status print status info ``` + ## roboclaw + Source: [drivers/roboclaw](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/roboclaw) @@ -1258,8 +1245,8 @@ the address `RBCLW_ADDRESS` needs to match the ESC configuration. The command to start this driver is: `$ roboclaw start ` - -### Usage +### Usage {#roboclaw_usage} + ``` roboclaw [arguments...] Commands: @@ -1269,11 +1256,13 @@ roboclaw [arguments...] status print status info ``` + ## rpm_capture + Source: [drivers/rpm_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm_capture) - -### Usage +### Usage {#rpm_capture_usage} + ``` rpm_capture [arguments...] Commands: @@ -1283,7 +1272,9 @@ rpm_capture [arguments...] status print status info ``` + ## safety_button + Source: [drivers/safety_button](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/safety_button) @@ -1292,8 +1283,8 @@ This module is responsible for the safety button. Pressing the safety button 3 times quickly will trigger a GCS pairing request. - -### Usage +### Usage {#safety_button_usage} + ``` safety_button [arguments...] Commands: @@ -1303,28 +1294,9 @@ safety_button [arguments...] status print status info ``` -## sbus_rc -Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) - -### Description -This module does SBUS RC input parsing. - - - -### Usage -``` -sbus_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` ## septentrio + Source: [drivers/gnss/septentrio](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gnss/septentrio) @@ -1353,8 +1325,8 @@ Perform warm reset of the receivers: gps reset warm ``` - -### Usage +### Usage {#septentrio_usage} + ``` septentrio [arguments...] Commands: @@ -1375,7 +1347,9 @@ septentrio [arguments...] reset Reset connected receiver cold|warm|hot Specify reset type ``` + ## sht3x + Source: [drivers/hygrometer/sht3x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/hygrometer/sht3x) @@ -1405,8 +1379,8 @@ sht3x reset Reinitialize senzor, reset flags - -### Usage +### Usage {#sht3x_usage} + ``` sht3x [arguments...] Commands: @@ -1429,7 +1403,9 @@ sht3x [arguments...] reset Reinitialize sensor ``` + ## tap_esc + Source: [drivers/tap_esc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/tap_esc) @@ -1451,8 +1427,8 @@ The module is typically started with: tap_esc start -d /dev/ttyS2 -n <1-8> ``` - -### Usage +### Usage {#tap_esc_usage} + ``` tap_esc [arguments...] Commands: @@ -1462,7 +1438,9 @@ tap_esc [arguments...] [-n ] Number of ESCs default: 4 ``` + ## tone_alarm + Source: [drivers/tone_alarm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/tone_alarm) @@ -1470,8 +1448,8 @@ Source: [drivers/tone_alarm](https://github.com/PX4/PX4-Autopilot/tree/main/src/ This module is responsible for the tone alarm. - -### Usage +### Usage {#tone_alarm_usage} + ``` tone_alarm [arguments...] Commands: @@ -1481,7 +1459,9 @@ tone_alarm [arguments...] status print status info ``` + ## uwb + Source: [drivers/uwb/uwb_sr150](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/uwb/uwb_sr150) @@ -1498,8 +1478,8 @@ Start the driver with a given device: uwb start -d /dev/ttyS2 ``` - -### Usage +### Usage {#uwb_usage} + ``` uwb [arguments...] Commands: @@ -1513,11 +1493,13 @@ uwb [arguments...] status ``` + ## vertiq_io + Source: [drivers/actuators/vertiq_io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/actuators/vertiq_io) - -### Usage +### Usage {#vertiq_io_usage} + ``` vertiq_io [arguments...] Commands: @@ -1528,7 +1510,9 @@ vertiq_io [arguments...] status print status info ``` + ## voxl2_io + Source: [drivers/voxl2_io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/voxl2_io) @@ -1538,8 +1522,8 @@ This module is responsible for driving the output pins. For boards without a sep px4io driver is used for main ones. - -### Usage +### Usage {#voxl2_io_usage} + ``` voxl2_io [arguments...] Commands: @@ -1557,7 +1541,9 @@ voxl2_io [arguments...] status print status info ``` + ## voxl_esc + Source: [drivers/actuators/voxl_esc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/actuators/voxl_esc) @@ -1574,8 +1560,8 @@ todo ``` - -### Usage +### Usage {#voxl_esc_usage} + ``` voxl_esc [arguments...] Commands: @@ -1616,11 +1602,13 @@ voxl_esc [arguments...] status print status info ``` + ## voxlpm + Source: [drivers/power_monitor/voxlpm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/voxlpm) - -### Usage +### Usage {#voxlpm_usage} + ``` voxlpm [arguments...] start @@ -1640,7 +1628,9 @@ voxlpm [arguments...] status print status info ``` + ## zenoh + Source: [modules/zenoh](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/zenoh) @@ -1648,8 +1638,8 @@ Source: [modules/zenoh](https://github.com/PX4/PX4-Autopilot/tree/main/src/modul Zenoh demo bridge - -### Usage +### Usage {#zenoh_usage} + ``` zenoh [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_airspeed_sensor.md b/docs/en/modules/modules_driver_airspeed_sensor.md index 2aede657f5..a1545bfe53 100644 --- a/docs/en/modules/modules_driver_airspeed_sensor.md +++ b/docs/en/modules/modules_driver_airspeed_sensor.md @@ -1,5 +1,7 @@ # Modules Reference: Airspeed Sensor (Driver) + ## asp5033 + Source: [drivers/differential_pressure/asp5033](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/asp5033) @@ -11,8 +13,8 @@ This is not included by default in firmware. It can be included with terminal co or in default.px4board with adding the line: "CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y" It can be enabled with the "SENS_EN_ASP5033" parameter set to 1. - -### Usage +### Usage {#asp5033_usage} + ``` asp5033 [arguments...] Commands: @@ -30,11 +32,13 @@ asp5033 [arguments...] status print status info ``` + ## auav + Source: [drivers/differential_pressure/auav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/auav) - -### Usage +### Usage {#auav_usage} + ``` auav [arguments...] Commands: @@ -54,11 +58,13 @@ auav [arguments...] status print status info ``` + ## ets_airspeed + Source: [drivers/differential_pressure/ets](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ets) - -### Usage +### Usage {#ets_airspeed_usage} + ``` ets_airspeed [arguments...] Commands: @@ -76,11 +82,13 @@ ets_airspeed [arguments...] status print status info ``` + ## ms4515 + Source: [drivers/differential_pressure/ms4515](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4515) - -### Usage +### Usage {#ms4515_usage} + ``` ms4515 [arguments...] Commands: @@ -98,11 +106,13 @@ ms4515 [arguments...] status print status info ``` + ## ms4525do + Source: [drivers/differential_pressure/ms4525do](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4525do) - -### Usage +### Usage {#ms4525do_usage} + ``` ms4525do [arguments...] Commands: @@ -120,11 +130,13 @@ ms4525do [arguments...] status print status info ``` + ## ms5525dso + Source: [drivers/differential_pressure/ms5525dso](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms5525dso) - -### Usage +### Usage {#ms5525dso_usage} + ``` ms5525dso [arguments...] Commands: @@ -142,11 +154,13 @@ ms5525dso [arguments...] status print status info ``` + ## sdp3x + Source: [drivers/differential_pressure/sdp3x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/sdp3x) - -### Usage +### Usage {#sdp3x_usage} + ``` sdp3x [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_baro.md b/docs/en/modules/modules_driver_baro.md index d54acc9201..be32c800ed 100644 --- a/docs/en/modules/modules_driver_baro.md +++ b/docs/en/modules/modules_driver_baro.md @@ -1,9 +1,11 @@ # Modules Reference: Baro (Driver) + ## bmp280 + Source: [drivers/barometer/bmp280](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp280) - -### Usage +### Usage {#bmp280_usage} + ``` bmp280 [arguments...] Commands: @@ -33,11 +35,13 @@ bmp280 [arguments...] status print status info ``` + ## bmp388 + Source: [drivers/barometer/bmp388](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp388) - -### Usage +### Usage {#bmp388_usage} + ``` bmp388 [arguments...] Commands: @@ -59,11 +63,13 @@ bmp388 [arguments...] status print status info ``` + ## bmp581 + Source: [drivers/barometer/bmp581](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp581) - -### Usage +### Usage {#bmp581_usage} + ``` bmp581 [arguments...] Commands: @@ -85,11 +91,13 @@ bmp581 [arguments...] status print status info ``` + ## dps310 + Source: [drivers/barometer/dps310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/dps310) - -### Usage +### Usage {#dps310_usage} + ``` dps310 [arguments...] Commands: @@ -119,11 +127,13 @@ dps310 [arguments...] status print status info ``` + ## icp101xx + Source: [drivers/barometer/invensense/icp101xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp101xx) - -### Usage +### Usage {#icp101xx_usage} + ``` icp101xx [arguments...] Commands: @@ -141,11 +151,13 @@ icp101xx [arguments...] status print status info ``` + ## icp201xx + Source: [drivers/barometer/invensense/icp201xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp201xx) - -### Usage +### Usage {#icp201xx_usage} + ``` icp201xx [arguments...] Commands: @@ -163,11 +175,13 @@ icp201xx [arguments...] status print status info ``` + ## lps22hb + Source: [drivers/barometer/lps22hb](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps22hb) - -### Usage +### Usage {#lps22hb_usage} + ``` lps22hb [arguments...] Commands: @@ -187,11 +201,13 @@ lps22hb [arguments...] status print status info ``` + ## lps25h + Source: [drivers/barometer/lps25h](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps25h) - -### Usage +### Usage {#lps25h_usage} + ``` lps25h [arguments...] Commands: @@ -211,11 +227,13 @@ lps25h [arguments...] status print status info ``` + ## lps33hw + Source: [drivers/barometer/lps33hw](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps33hw) - -### Usage +### Usage {#lps33hw_usage} + ``` lps33hw [arguments...] Commands: @@ -238,11 +256,13 @@ lps33hw [arguments...] status print status info ``` + ## mpc2520 + Source: [drivers/barometer/maiertek/mpc2520](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/maiertek/mpc2520) - -### Usage +### Usage {#mpc2520_usage} + ``` mpc2520 [arguments...] Commands: @@ -260,11 +280,13 @@ mpc2520 [arguments...] status print status info ``` + ## mpl3115a2 + Source: [drivers/barometer/mpl3115a2](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/mpl3115a2) - -### Usage +### Usage {#mpl3115a2_usage} + ``` mpl3115a2 [arguments...] Commands: @@ -282,11 +304,13 @@ mpl3115a2 [arguments...] status print status info ``` + ## ms5611 + Source: [drivers/barometer/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - -### Usage +### Usage {#ms5611_usage} + ``` ms5611 [arguments...] Commands: @@ -316,11 +340,13 @@ ms5611 [arguments...] status print status info ``` + ## ms5837 + Source: [drivers/barometer/ms5837](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5837) - -### Usage +### Usage {#ms5837_usage} + ``` ms5837 [arguments...] Commands: @@ -336,11 +362,13 @@ ms5837 [arguments...] status print status info ``` + ## spa06 + Source: [drivers/barometer/goertek/spa06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spa06) - -### Usage +### Usage {#spa06_usage} + ``` spa06 [arguments...] Commands: @@ -370,11 +398,13 @@ spa06 [arguments...] status print status info ``` + ## spl06 + Source: [drivers/barometer/goertek/spl06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spl06) - -### Usage +### Usage {#spl06_usage} + ``` spl06 [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_camera.md b/docs/en/modules/modules_driver_camera.md index a214259a98..58f3cfb45d 100644 --- a/docs/en/modules/modules_driver_camera.md +++ b/docs/en/modules/modules_driver_camera.md @@ -1,5 +1,7 @@ # Modules Reference: Camera (Driver) + ## camera_trigger + Source: [drivers/camera_trigger](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/camera_trigger) @@ -33,8 +35,8 @@ In particular: [Setup/usage information](../camera/index.md). - -### Usage +### Usage {#camera_trigger_usage} + ``` camera_trigger [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_distance_sensor.md b/docs/en/modules/modules_driver_distance_sensor.md index 96c88fc6fc..6d34f31794 100644 --- a/docs/en/modules/modules_driver_distance_sensor.md +++ b/docs/en/modules/modules_driver_distance_sensor.md @@ -1,5 +1,7 @@ # Modules Reference: Distance Sensor (Driver) + ## afbrs50 + Source: [drivers/distance_sensor/broadcom/afbrs50](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/broadcom/afbrs50) @@ -18,8 +20,8 @@ Stop driver afbrs50 stop ``` - -### Usage +### Usage {#afbrs50_usage} + ``` afbrs50 [arguments...] Commands: @@ -32,11 +34,13 @@ afbrs50 [arguments...] stop Stop driver ``` + ## gy_us42 + Source: [drivers/distance_sensor/gy_us42](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/gy_us42) - -### Usage +### Usage {#gy_us42_usage} + ``` gy_us42 [arguments...] Commands: @@ -54,7 +58,9 @@ gy_us42 [arguments...] status print status info ``` + ## leddar_one + Source: [drivers/distance_sensor/leddar_one](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/leddar_one) @@ -77,8 +83,8 @@ Stop driver leddar_one stop ``` - -### Usage +### Usage {#leddar_one_usage} + ``` leddar_one [arguments...] Commands: @@ -89,7 +95,9 @@ leddar_one [arguments...] stop Stop driver ``` + ## lightware_laser_i2c + Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_i2c) @@ -99,8 +107,8 @@ I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF1 Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html - -### Usage +### Usage {#lightware_laser_i2c_usage} + ``` lightware_laser_i2c [arguments...] Commands: @@ -120,7 +128,9 @@ lightware_laser_i2c [arguments...] status print status info ``` + ## lightware_laser_serial + Source: [drivers/distance_sensor/lightware_laser_serial](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_serial) @@ -143,8 +153,8 @@ Stop driver lightware_laser_serial stop ``` - -### Usage +### Usage {#lightware_laser_serial_usage} + ``` lightware_laser_serial [arguments...] Commands: @@ -155,7 +165,9 @@ lightware_laser_serial [arguments...] stop Stop driver ``` + ## lightware_sf45_serial + Source: [drivers/distance_sensor/lightware_sf45_serial](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_sf45_serial) @@ -175,8 +187,8 @@ Stop driver lightware_sf45_serial stop ``` - -### Usage +### Usage {#lightware_sf45_serial_usage} + ``` lightware_sf45_serial [arguments...] Commands: @@ -185,7 +197,9 @@ lightware_sf45_serial [arguments...] stop Stop driver ``` + ## ll40ls + Source: [drivers/distance_sensor/ll40ls_pwm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/ll40ls_pwm) @@ -197,8 +211,8 @@ The sensor/driver must be enabled using the parameter SENS_EN_LL40LS. Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html - -### Usage +### Usage {#ll40ls_usage} + ``` ll40ls [arguments...] Commands: @@ -210,11 +224,13 @@ ll40ls [arguments...] stop Stop driver ``` + ## mappydot + Source: [drivers/distance_sensor/mappydot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mappydot) - -### Usage +### Usage {#mappydot_usage} + ``` mappydot [arguments...] Commands: @@ -230,11 +246,13 @@ mappydot [arguments...] status print status info ``` + ## mb12xx + Source: [drivers/distance_sensor/mb12xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mb12xx) - -### Usage +### Usage {#mb12xx_usage} + ``` mb12xx [arguments...] Commands: @@ -254,7 +272,9 @@ mb12xx [arguments...] status print status info ``` + ## pga460 + Source: [drivers/distance_sensor/pga460](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/pga460) @@ -270,8 +290,8 @@ running. A simple algorithm to detect false readings is implemented at the drive the quality of data that is being published. The driver will not publish data at all if it deems the sensor data to be invalid or unstable. - -### Usage +### Usage {#pga460_usage} + ``` pga460 [arguments...] Commands: @@ -284,11 +304,13 @@ pga460 [arguments...] help ``` + ## srf02 + Source: [drivers/distance_sensor/srf02](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/srf02) - -### Usage +### Usage {#srf02_usage} + ``` srf02 [arguments...] Commands: @@ -308,7 +330,9 @@ srf02 [arguments...] status print status info ``` + ## srf05 + Source: [drivers/distance_sensor/srf05](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/srf05) @@ -319,8 +343,8 @@ Source: [drivers/distance_sensor/srf05](https://github.com/PX4/PX4-Autopilot/tre The sensor/driver must be enabled using the parameter SENS_EN_HXSRX0X. - -### Usage +### Usage {#srf05_usage} + ``` srf05 [arguments...] Commands: @@ -336,7 +360,9 @@ srf05 [arguments...] status print status info ``` + ## teraranger + Source: [drivers/distance_sensor/teraranger](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/teraranger) @@ -348,8 +374,8 @@ The sensor/driver must be enabled using the parameter SENS_EN_TRANGER. Setup/usage information: https://docs.px4.io/main/en/sensor/rangefinders.html#teraranger-rangefinders - -### Usage +### Usage {#teraranger_usage} + ``` teraranger [arguments...] Commands: @@ -369,11 +395,13 @@ teraranger [arguments...] status print status info ``` + ## tf02pro + Source: [drivers/distance_sensor/tf02pro](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/tf02pro) - -### Usage +### Usage {#tf02pro_usage} + ``` tf02pro [arguments...] Commands: @@ -393,7 +421,9 @@ tf02pro [arguments...] status print status info ``` + ## tfmini + Source: [drivers/distance_sensor/tfmini](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/tfmini) @@ -416,8 +446,8 @@ Stop driver tfmini stop ``` - -### Usage +### Usage {#tfmini_usage} + ``` tfmini [arguments...] Commands: @@ -432,7 +462,9 @@ tfmini [arguments...] status Print driver status ``` + ## ulanding_radar + Source: [drivers/distance_sensor/ulanding_radar](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/ulanding_radar) @@ -453,8 +485,8 @@ Stop driver ulanding_radar stop ``` - -### Usage +### Usage {#ulanding_radar_usage} + ``` ulanding_radar [arguments...] Commands: @@ -466,11 +498,13 @@ ulanding_radar [arguments...] stop Stop driver ``` + ## vl53l0x + Source: [drivers/distance_sensor/vl53l0x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l0x) - -### Usage +### Usage {#vl53l0x_usage} + ``` vl53l0x [arguments...] Commands: @@ -490,11 +524,13 @@ vl53l0x [arguments...] status print status info ``` + ## vl53l1x + Source: [drivers/distance_sensor/vl53l1x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l1x) - -### Usage +### Usage {#vl53l1x_usage} + ``` vl53l1x [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_imu.md b/docs/en/modules/modules_driver_imu.md index 32d7a9bc24..67f9a2713b 100644 --- a/docs/en/modules/modules_driver_imu.md +++ b/docs/en/modules/modules_driver_imu.md @@ -1,9 +1,11 @@ # Modules Reference: Imu (Driver) + ## adis16448 + Source: [drivers/imu/analog_devices/adis16448](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16448) - -### Usage +### Usage {#adis16448_usage} + ``` adis16448 [arguments...] Commands: @@ -23,11 +25,13 @@ adis16448 [arguments...] status print status info ``` + ## adis16470 + Source: [drivers/imu/analog_devices/adis16470](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16470) - -### Usage +### Usage {#adis16470_usage} + ``` adis16470 [arguments...] Commands: @@ -47,11 +51,13 @@ adis16470 [arguments...] status print status info ``` + ## adis16477 + Source: [drivers/imu/analog_devices/adis16477](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16477) - -### Usage +### Usage {#adis16477_usage} + ``` adis16477 [arguments...] Commands: @@ -71,11 +77,13 @@ adis16477 [arguments...] status print status info ``` + ## adis16497 + Source: [drivers/imu/analog_devices/adis16497](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16497) - -### Usage +### Usage {#adis16497_usage} + ``` adis16497 [arguments...] Commands: @@ -95,11 +103,13 @@ adis16497 [arguments...] status print status info ``` + ## adis16507 + Source: [drivers/imu/analog_devices/adis16507](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16507) - -### Usage +### Usage {#adis16507_usage} + ``` adis16507 [arguments...] Commands: @@ -119,11 +129,13 @@ adis16507 [arguments...] status print status info ``` + ## bmi055 + Source: [drivers/imu/bosch/bmi055](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi055) - -### Usage +### Usage {#bmi055_usage} + ``` bmi055 [arguments...] Commands: @@ -145,11 +157,13 @@ bmi055 [arguments...] status print status info ``` + ## bmi085 + Source: [drivers/imu/bosch/bmi085](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi085) - -### Usage +### Usage {#bmi085_usage} + ``` bmi085 [arguments...] Commands: @@ -171,11 +185,13 @@ bmi085 [arguments...] status print status info ``` + ## bmi088 + Source: [drivers/imu/bosch/bmi088](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088) - -### Usage +### Usage {#bmi088_usage} + ``` bmi088 [arguments...] Commands: @@ -197,11 +213,13 @@ bmi088 [arguments...] status print status info ``` + ## bmi088_i2c + Source: [drivers/imu/bosch/bmi088_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088_i2c) - -### Usage +### Usage {#bmi088_i2c_usage} + ``` bmi088_i2c [arguments...] Commands: @@ -223,11 +241,13 @@ bmi088_i2c [arguments...] status print status info ``` + ## bmi270 + Source: [drivers/imu/bosch/bmi270](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi270) - -### Usage +### Usage {#bmi270_usage} + ``` bmi270 [arguments...] Commands: @@ -247,11 +267,13 @@ bmi270 [arguments...] status print status info ``` + ## fxas21002c + Source: [drivers/imu/nxp/fxas21002c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxas21002c) - -### Usage +### Usage {#fxas21002c_usage} + ``` fxas21002c [arguments...] Commands: @@ -279,11 +301,13 @@ fxas21002c [arguments...] status print status info ``` + ## fxos8701cq + Source: [drivers/imu/nxp/fxos8701cq](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxos8701cq) - -### Usage +### Usage {#fxos8701cq_usage} + ``` fxos8701cq [arguments...] Commands: @@ -311,11 +335,13 @@ fxos8701cq [arguments...] status print status info ``` + ## iam20680hp + Source: [drivers/imu/invensense/iam20680hp](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iam20680hp) - -### Usage +### Usage {#iam20680hp_usage} + ``` iam20680hp [arguments...] Commands: @@ -335,11 +361,13 @@ iam20680hp [arguments...] status print status info ``` + ## icm20602 + Source: [drivers/imu/invensense/icm20602](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20602) - -### Usage +### Usage {#icm20602_usage} + ``` icm20602 [arguments...] Commands: @@ -359,11 +387,13 @@ icm20602 [arguments...] status print status info ``` + ## icm20608g + Source: [drivers/imu/invensense/icm20608g](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20608g) - -### Usage +### Usage {#icm20608g_usage} + ``` icm20608g [arguments...] Commands: @@ -383,11 +413,13 @@ icm20608g [arguments...] status print status info ``` + ## icm20649 + Source: [drivers/imu/invensense/icm20649](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20649) - -### Usage +### Usage {#icm20649_usage} + ``` icm20649 [arguments...] Commands: @@ -407,11 +439,13 @@ icm20649 [arguments...] status print status info ``` + ## icm20689 + Source: [drivers/imu/invensense/icm20689](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20689) - -### Usage +### Usage {#icm20689_usage} + ``` icm20689 [arguments...] Commands: @@ -431,11 +465,13 @@ icm20689 [arguments...] status print status info ``` + ## icm20948 + Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - -### Usage +### Usage {#icm20948_usage} + ``` icm20948 [arguments...] Commands: @@ -456,11 +492,13 @@ icm20948 [arguments...] status print status info ``` + ## icm20948_i2c_passthrough + Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - -### Usage +### Usage {#icm20948_i2c_passthrough_usage} + ``` icm20948_i2c_passthrough [arguments...] Commands: @@ -478,11 +516,13 @@ icm20948_i2c_passthrough [arguments...] status print status info ``` + ## icm40609d + Source: [drivers/imu/invensense/icm40609d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm40609d) - -### Usage +### Usage {#icm40609d_usage} + ``` icm40609d [arguments...] Commands: @@ -502,11 +542,13 @@ icm40609d [arguments...] status print status info ``` + ## icm42605 + Source: [drivers/imu/invensense/icm42605](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42605) - -### Usage +### Usage {#icm42605_usage} + ``` icm42605 [arguments...] Commands: @@ -526,11 +568,13 @@ icm42605 [arguments...] status print status info ``` + ## icm42670p + Source: [drivers/imu/invensense/icm42670p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42670p) - -### Usage +### Usage {#icm42670p_usage} + ``` icm42670p [arguments...] Commands: @@ -550,11 +594,13 @@ icm42670p [arguments...] status print status info ``` + ## icm42688p + Source: [drivers/imu/invensense/icm42688p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42688p) - -### Usage +### Usage {#icm42688p_usage} + ``` icm42688p [arguments...] Commands: @@ -577,11 +623,13 @@ icm42688p [arguments...] status print status info ``` + ## icm45686 + Source: [drivers/imu/invensense/icm45686](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm45686) - -### Usage +### Usage {#icm45686_usage} + ``` icm45686 [arguments...] Commands: @@ -603,11 +651,13 @@ icm45686 [arguments...] status print status info ``` + ## iim42652 + Source: [drivers/imu/invensense/iim42652](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42652) - -### Usage +### Usage {#iim42652_usage} + ``` iim42652 [arguments...] Commands: @@ -629,11 +679,13 @@ iim42652 [arguments...] status print status info ``` + ## iim42653 + Source: [drivers/imu/invensense/iim42653](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42653) - -### Usage +### Usage {#iim42653_usage} + ``` iim42653 [arguments...] Commands: @@ -655,11 +707,13 @@ iim42653 [arguments...] status print status info ``` + ## l3gd20 + Source: [drivers/imu/st/l3gd20](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/l3gd20) - -### Usage +### Usage {#l3gd20_usage} + ``` l3gd20 [arguments...] Commands: @@ -683,11 +737,13 @@ l3gd20 [arguments...] status print status info ``` + ## lsm303d + Source: [drivers/imu/st/lsm303d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm303d) - -### Usage +### Usage {#lsm303d_usage} + ``` lsm303d [arguments...] Commands: @@ -707,11 +763,13 @@ lsm303d [arguments...] status print status info ``` + ## lsm9ds1 + Source: [drivers/imu/st/lsm9ds1](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm9ds1) - -### Usage +### Usage {#lsm9ds1_usage} + ``` lsm9ds1 [arguments...] Commands: @@ -731,11 +789,13 @@ lsm9ds1 [arguments...] status print status info ``` + ## mpu6000 + Source: [drivers/imu/invensense/mpu6000](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6000) - -### Usage +### Usage {#mpu6000_usage} + ``` mpu6000 [arguments...] Commands: @@ -755,11 +815,13 @@ mpu6000 [arguments...] status print status info ``` + ## mpu9250 + Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - -### Usage +### Usage {#mpu9250_usage} + ``` mpu9250 [arguments...] Commands: @@ -780,11 +842,13 @@ mpu9250 [arguments...] status print status info ``` + ## mpu9250_i2c + Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - -### Usage +### Usage {#mpu9250_i2c_usage} + ``` mpu9250_i2c [arguments...] Commands: @@ -804,11 +868,13 @@ mpu9250_i2c [arguments...] status print status info ``` + ## mpu9520 + Source: [drivers/imu/invensense/mpu6500](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6500) - -### Usage +### Usage {#mpu9520_usage} + ``` mpu9520 [arguments...] Commands: @@ -828,11 +894,13 @@ mpu9520 [arguments...] status print status info ``` + ## sch16t + Source: [drivers/imu/murata/sch16t](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/murata/sch16t) - -### Usage +### Usage {#sch16t_usage} + ``` sch16t [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_ins.md b/docs/en/modules/modules_driver_ins.md index a108ed5057..5425ab01f2 100644 --- a/docs/en/modules/modules_driver_ins.md +++ b/docs/en/modules/modules_driver_ins.md @@ -1,5 +1,7 @@ # Modules Reference: Ins (Driver) + ## vectornav + Source: [drivers/ins/vectornav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/vectornav) @@ -22,8 +24,8 @@ Stop driver vectornav stop ``` - -### Usage +### Usage {#vectornav_usage} + ``` vectornav [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_magnetometer.md b/docs/en/modules/modules_driver_magnetometer.md index 45719cfa1e..8d527cfa4e 100644 --- a/docs/en/modules/modules_driver_magnetometer.md +++ b/docs/en/modules/modules_driver_magnetometer.md @@ -1,9 +1,11 @@ # Modules Reference: Magnetometer (Driver) + ## ak09916 + Source: [drivers/magnetometer/akm/ak09916](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak09916) - -### Usage +### Usage {#ak09916_usage} + ``` ak09916 [arguments...] Commands: @@ -23,11 +25,13 @@ ak09916 [arguments...] status print status info ``` + ## ak8963 + Source: [drivers/magnetometer/akm/ak8963](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak8963) - -### Usage +### Usage {#ak8963_usage} + ``` ak8963 [arguments...] Commands: @@ -47,11 +51,13 @@ ak8963 [arguments...] status print status info ``` + ## bmm150 + Source: [drivers/magnetometer/bosch/bmm150](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm150) - -### Usage +### Usage {#bmm150_usage} + ``` bmm150 [arguments...] Commands: @@ -71,11 +77,13 @@ bmm150 [arguments...] status print status info ``` + ## bmm350 + Source: [drivers/magnetometer/bosch/bmm350](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm350) - -### Usage +### Usage {#bmm350_usage} + ``` bmm350 [arguments...] Commands: @@ -95,11 +103,13 @@ bmm350 [arguments...] status print status info ``` + ## hmc5883 + Source: [drivers/magnetometer/hmc5883](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/hmc5883) - -### Usage +### Usage {#hmc5883_usage} + ``` hmc5883 [arguments...] Commands: @@ -122,11 +132,13 @@ hmc5883 [arguments...] status print status info ``` + ## iis2mdc + Source: [drivers/magnetometer/st/iis2mdc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/st/iis2mdc) - -### Usage +### Usage {#iis2mdc_usage} + ``` iis2mdc [arguments...] Commands: @@ -144,11 +156,13 @@ iis2mdc [arguments...] status print status info ``` + ## ist8308 + Source: [drivers/magnetometer/isentek/ist8308](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8308) - -### Usage +### Usage {#ist8308_usage} + ``` ist8308 [arguments...] Commands: @@ -168,11 +182,13 @@ ist8308 [arguments...] status print status info ``` + ## ist8310 + Source: [drivers/magnetometer/isentek/ist8310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8310) - -### Usage +### Usage {#ist8310_usage} + ``` ist8310 [arguments...] Commands: @@ -192,11 +208,13 @@ ist8310 [arguments...] status print status info ``` + ## lis3mdl + Source: [drivers/magnetometer/lis3mdl](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lis3mdl) - -### Usage +### Usage {#lis3mdl_usage} + ``` lis3mdl [arguments...] Commands: @@ -222,11 +240,13 @@ lis3mdl [arguments...] status print status info ``` + ## lsm9ds1_mag + Source: [drivers/magnetometer/lsm9ds1_mag](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm9ds1_mag) - -### Usage +### Usage {#lsm9ds1_mag_usage} + ``` lsm9ds1_mag [arguments...] Commands: @@ -246,11 +266,13 @@ lsm9ds1_mag [arguments...] status print status info ``` + ## mmc5983ma + Source: [drivers/magnetometer/memsic/mmc5983ma](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/memsic/mmc5983ma) - -### Usage +### Usage {#mmc5983ma_usage} + ``` mmc5983ma [arguments...] Commands: @@ -276,11 +298,13 @@ mmc5983ma [arguments...] status print status info ``` + ## qmc5883l + Source: [drivers/magnetometer/qmc5883l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/qmc5883l) - -### Usage +### Usage {#qmc5883l_usage} + ``` qmc5883l [arguments...] Commands: @@ -300,11 +324,13 @@ qmc5883l [arguments...] status print status info ``` + ## rm3100 + Source: [drivers/magnetometer/rm3100](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/rm3100) - -### Usage +### Usage {#rm3100_usage} + ``` rm3100 [arguments...] Commands: @@ -326,11 +352,13 @@ rm3100 [arguments...] status print status info ``` + ## vcm1193l + Source: [drivers/magnetometer/vtrantech/vcm1193l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/vtrantech/vcm1193l) - -### Usage +### Usage {#vcm1193l_usage} + ``` vcm1193l [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_optical_flow.md b/docs/en/modules/modules_driver_optical_flow.md index 2d2b25e45b..2c734b5c3f 100644 --- a/docs/en/modules/modules_driver_optical_flow.md +++ b/docs/en/modules/modules_driver_optical_flow.md @@ -1,5 +1,7 @@ # Modules Reference: Optical Flow (Driver) + ## thoneflow + Source: [drivers/optical_flow/thoneflow](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/thoneflow) @@ -22,8 +24,8 @@ Stop driver thoneflow stop ``` - -### Usage +### Usage {#thoneflow_usage} + ``` thoneflow [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_radio_control.md b/docs/en/modules/modules_driver_radio_control.md new file mode 100644 index 0000000000..98489438e5 --- /dev/null +++ b/docs/en/modules/modules_driver_radio_control.md @@ -0,0 +1,126 @@ +# Modules Reference: Radio Control (Driver) + +## crsf_rc + +Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) + + +### Description +This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data + + +### Usage {#crsf_rc_usage} + +``` +crsf_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## dsm_rc + +Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) + + +### Description +This module does Spektrum DSM RC input parsing. + + +### Usage {#dsm_rc_usage} + +``` +dsm_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## ghst_rc + +Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) + + +### Description +This module does Ghost (GHST) RC input parsing. + + +### Usage {#ghst_rc_usage} + +``` +ghst_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## rc_input + +Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) + + +### Description +This module does the RC input parsing and auto-selecting the method. Supported methods are: +- PPM +- SBUS +- DSM +- SUMD +- ST24 +- TBS Crossfire (CRSF) + + +### Usage {#rc_input_usage} + +``` +rc_input [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## sbus_rc + +Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) + + +### Description +This module does SBUS RC input parsing. + + +### Usage {#sbus_rc_usage} + +``` +sbus_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` diff --git a/docs/en/modules/modules_driver_rpm_sensor.md b/docs/en/modules/modules_driver_rpm_sensor.md index f5cf246161..b4d7b95243 100644 --- a/docs/en/modules/modules_driver_rpm_sensor.md +++ b/docs/en/modules/modules_driver_rpm_sensor.md @@ -1,9 +1,11 @@ # Modules Reference: Rpm Sensor (Driver) + ## pcf8583 + Source: [drivers/rpm/pcf8583](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm/pcf8583) - -### Usage +### Usage {#pcf8583_usage} + ``` pcf8583 [arguments...] Commands: diff --git a/docs/en/modules/modules_driver_transponder.md b/docs/en/modules/modules_driver_transponder.md index 9f7d8ffaa9..799f9a9179 100644 --- a/docs/en/modules/modules_driver_transponder.md +++ b/docs/en/modules/modules_driver_transponder.md @@ -1,5 +1,7 @@ # Modules Reference: Transponder (Driver) + ## sagetech_mxs + Source: [drivers/transponder/sagetech_mxs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/transponder/sagetech_mxs) @@ -21,8 +23,8 @@ Source: [drivers/transponder/sagetech_mxs](https://github.com/PX4/PX4-Autopilot/ Set the Squawk Code $ sagetech_mxs squawk 1200 - -### Usage +### Usage {#sagetech_mxs_usage} + ``` sagetech_mxs [arguments...] Commands: diff --git a/docs/en/modules/modules_estimator.md b/docs/en/modules/modules_estimator.md index 5af631e9f6..71041bcd50 100644 --- a/docs/en/modules/modules_estimator.md +++ b/docs/en/modules/modules_estimator.md @@ -1,6 +1,9 @@ # Modules Reference: Estimator + + ## AttitudeEstimatorQ + Source: [modules/attitude_estimator_q](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/attitude_estimator_q) @@ -8,8 +11,8 @@ Source: [modules/attitude_estimator_q](https://github.com/PX4/PX4-Autopilot/tree Attitude estimator q. - -### Usage +### Usage {#AttitudeEstimatorQ_usage} + ``` AttitudeEstimatorQ [arguments...] Commands: @@ -19,7 +22,9 @@ AttitudeEstimatorQ [arguments...] status print status info ``` + ## airspeed_estimator + Source: [modules/airspeed_selector](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/airspeed_selector) @@ -33,8 +38,8 @@ the estimation of a scale factor from IAS to CAS, it runs several wind estimator and also publishes those. - -### Usage +### Usage {#airspeed_estimator_usage} + ``` airspeed_estimator [arguments...] Commands: @@ -44,7 +49,9 @@ airspeed_estimator [arguments...] status print status info ``` + ## ekf2 + Source: [modules/ekf2](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/ekf2) @@ -57,8 +64,8 @@ ekf2 can be started in replay mode (`-r`): in this mode, it does not access the timestamps from the sensor topics. - -### Usage +### Usage {#ekf2_usage} + ``` ekf2 [arguments...] Commands: @@ -73,7 +80,9 @@ ekf2 [arguments...] select_instance Request switch to new estimator instance Specify desired estimator instance ``` + ## local_position_estimator + Source: [modules/local_position_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/local_position_estimator) @@ -81,8 +90,8 @@ Source: [modules/local_position_estimator](https://github.com/PX4/PX4-Autopilot/ Attitude and position estimator using an Extended Kalman Filter. - -### Usage +### Usage {#local_position_estimator_usage} + ``` local_position_estimator [arguments...] Commands: @@ -92,15 +101,17 @@ local_position_estimator [arguments...] status print status info ``` + ## mc_hover_thrust_estimator + Source: [modules/mc_hover_thrust_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_hover_thrust_estimator) ### Description - -### Usage +### Usage {#mc_hover_thrust_estimator_usage} + ``` mc_hover_thrust_estimator [arguments...] Commands: diff --git a/docs/en/modules/modules_simulation.md b/docs/en/modules/modules_simulation.md index e1e1d1333b..18c267517b 100644 --- a/docs/en/modules/modules_simulation.md +++ b/docs/en/modules/modules_simulation.md @@ -1,6 +1,9 @@ # Modules Reference: Simulation + + ## simulator_sih + Source: [modules/simulation/simulator_sih](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih) @@ -22,8 +25,8 @@ Most of the variables are declared global in the .hpp file to avoid stack overfl - -### Usage +### Usage {#simulator_sih_usage} + ``` simulator_sih [arguments...] Commands: diff --git a/docs/en/modules/modules_system.md b/docs/en/modules/modules_system.md index caf39dbede..3bd92fa971 100644 --- a/docs/en/modules/modules_system.md +++ b/docs/en/modules/modules_system.md @@ -1,6 +1,9 @@ # Modules Reference: System + + ## battery_simulator + Source: [modules/simulation/battery_simulator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/battery_simulator) @@ -8,8 +11,8 @@ Source: [modules/simulation/battery_simulator](https://github.com/PX4/PX4-Autopi - -### Usage +### Usage {#battery_simulator_usage} + ``` battery_simulator [arguments...] Commands: @@ -19,7 +22,9 @@ battery_simulator [arguments...] status print status info ``` + ## battery_status + Source: [modules/battery_status](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/battery_status) @@ -33,8 +38,8 @@ The provided functionality includes: It runs in its own thread and polls on the currently selected gyro topic. - -### Usage +### Usage {#battery_status_usage} + ``` battery_status [arguments...] Commands: @@ -44,7 +49,9 @@ battery_status [arguments...] status print status info ``` + ## camera_feedback + Source: [modules/camera_feedback](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/camera_feedback) @@ -71,8 +78,8 @@ For the topics that are not discarded it creates a `CameraCapture` topic with th from the `CameraTrigger` and position information from the vehicle. - -### Usage +### Usage {#camera_feedback_usage} + ``` camera_feedback [arguments...] Commands: @@ -82,7 +89,9 @@ camera_feedback [arguments...] status print status info ``` + ## cdcacm_autostart + Source: [drivers/cdcacm_autostart](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/cdcacm_autostart) @@ -92,8 +101,8 @@ The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin and continue to check for VBUS and start mavlink once it is detected. - -### Usage +### Usage {#cdcacm_autostart_usage} + ``` cdcacm_autostart [arguments...] Commands: @@ -103,15 +112,17 @@ cdcacm_autostart [arguments...] status print status info ``` + ## commander + Source: [modules/commander](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/commander) ### Description The commander module contains the state machine for mode switching and failsafe behavior. - -### Usage +### Usage {#commander_usage} + ``` commander [arguments...] Commands: @@ -157,7 +168,9 @@ commander [arguments...] status print status info ``` + ## dataman + Source: [modules/dataman](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/dataman) @@ -174,8 +187,8 @@ Each type has a specific type and a fixed maximum amount of storage items, so th Reading and writing a single item is always atomic. - -### Usage +### Usage {#dataman_usage} + ``` dataman [arguments...] Commands: @@ -191,7 +204,9 @@ dataman [arguments...] status print status info ``` + ## dmesg + Source: [systemcmds/dmesg](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dmesg) @@ -207,14 +222,16 @@ Keep printing all messages in the background: dmesg -f & ``` - -### Usage +### Usage {#dmesg_usage} + ``` dmesg [arguments...] Commands: [-f] Follow: wait for new messages ``` + ## esc_battery + Source: [modules/esc_battery](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/esc_battery) @@ -222,8 +239,8 @@ Source: [modules/esc_battery](https://github.com/PX4/PX4-Autopilot/tree/main/src This implements using information from the ESC status and publish it as battery status. - -### Usage +### Usage {#esc_battery_usage} + ``` esc_battery [arguments...] Commands: @@ -233,7 +250,9 @@ esc_battery [arguments...] status print status info ``` + ## gyro_calibration + Source: [modules/gyro_calibration](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/gyro_calibration) @@ -241,8 +260,8 @@ Source: [modules/gyro_calibration](https://github.com/PX4/PX4-Autopilot/tree/mai Simple online gyroscope calibration. - -### Usage +### Usage {#gyro_calibration_usage} + ``` gyro_calibration [arguments...] Commands: @@ -252,15 +271,17 @@ gyro_calibration [arguments...] status print status info ``` + ## gyro_fft + Source: [modules/gyro_fft](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/gyro_fft) ### Description - -### Usage +### Usage {#gyro_fft_usage} + ``` gyro_fft [arguments...] Commands: @@ -270,7 +291,9 @@ gyro_fft [arguments...] status print status info ``` + ## heater + Source: [drivers/heater](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/heater) @@ -279,8 +302,8 @@ Background process running periodically on the LP work queue to regulate IMU tem This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI. - -### Usage +### Usage {#heater_usage} + ``` heater [arguments...] Commands: @@ -290,7 +313,9 @@ heater [arguments...] status print status info ``` + ## i2c_launcher + Source: [systemcmds/i2c_launcher](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/i2c_launcher) @@ -298,8 +323,8 @@ Source: [systemcmds/i2c_launcher](https://github.com/PX4/PX4-Autopilot/tree/main Daemon that starts drivers based on found I2C devices. - -### Usage +### Usage {#i2c_launcher_usage} + ``` i2c_launcher [arguments...] Commands: @@ -310,7 +335,9 @@ i2c_launcher [arguments...] status print status info ``` + ## internal_combustion_engine_control + Source: [modules/internal_combustion_engine_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/internal_combustion_engine_control) @@ -363,8 +390,8 @@ The architecture is as shown below: - -### Usage +### Usage {#internal_combustion_engine_control_usage} + ``` internal_combustion_engine_control [arguments...] Commands: @@ -374,7 +401,9 @@ internal_combustion_engine_control [arguments...] status print status info ``` + ## land_detector + Source: [modules/land_detector](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/land_detector) @@ -401,8 +430,8 @@ position controller sets the thrust setpoint to zero. The module runs periodically on the HP work queue. - -### Usage +### Usage {#land_detector_usage} + ``` land_detector [arguments...] Commands: @@ -413,7 +442,9 @@ land_detector [arguments...] status print status info ``` + ## load_mon + Source: [modules/load_mon](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/load_mon) @@ -424,8 +455,8 @@ usage and publish the `cpuload` topic. On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output, which will also appear in the log file. - -### Usage +### Usage {#load_mon_usage} + ``` load_mon [arguments...] Commands: @@ -435,7 +466,9 @@ load_mon [arguments...] status print status info ``` + ## logger + Source: [modules/logger](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/logger) @@ -475,8 +508,8 @@ Or if already running: logger on ``` - -### Usage +### Usage {#logger_usage} + ``` logger [arguments...] Commands: @@ -509,15 +542,17 @@ logger [arguments...] status print status info ``` + ## mag_bias_estimator + Source: [modules/mag_bias_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mag_bias_estimator) ### Description Online magnetometer bias estimator. - -### Usage +### Usage {#mag_bias_estimator_usage} + ``` mag_bias_estimator [arguments...] Commands: @@ -527,7 +562,9 @@ mag_bias_estimator [arguments...] status print status info ``` + ## manual_control + Source: [modules/manual_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/manual_control) @@ -535,8 +572,8 @@ Source: [modules/manual_control](https://github.com/PX4/PX4-Autopilot/tree/main/ Module consuming manual_control_inputs publishing one manual_control_setpoint. - -### Usage +### Usage {#manual_control_usage} + ``` manual_control [arguments...] Commands: @@ -546,7 +583,9 @@ manual_control [arguments...] status print status info ``` + ## netman + Source: [systemcmds/netman](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/netman) @@ -580,8 +619,8 @@ Source: [systemcmds/netman](https://github.com/PX4/PX4-Autopilot/tree/main/src/s $ netman show # display current settings. $ netman update -i eth0 # do an update - -### Usage +### Usage {#netman_usage} + ``` netman [arguments...] Commands: @@ -594,7 +633,9 @@ netman [arguments...] [-i ] Set the interface name default: eth0 ``` + ## pwm_input + Source: [drivers/pwm_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/pwm_input) @@ -602,8 +643,8 @@ Source: [drivers/pwm_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/d Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input` message. - -### Usage +### Usage {#pwm_input_usage} + ``` pwm_input [arguments...] Commands: @@ -613,7 +654,9 @@ pwm_input [arguments...] status print status info ``` + ## rc_update + Source: [modules/rc_update](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/rc_update) @@ -626,8 +669,8 @@ and then publish as `rc_channels` and `manual_control_input`. To reduce control latency, the module is scheduled on input_rc publications. - -### Usage +### Usage {#rc_update_usage} + ``` rc_update [arguments...] Commands: @@ -637,7 +680,9 @@ rc_update [arguments...] status print status info ``` + ## replay + Source: [modules/replay](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/replay) @@ -658,8 +703,8 @@ the log. The replay procedure is documented on the [System-wide Replay](https://docs.px4.io/main/en/debug/system_wide_replay.html) page. - -### Usage +### Usage {#replay_usage} + ``` replay [arguments...] Commands: @@ -673,7 +718,9 @@ replay [arguments...] status print status info ``` + ## send_event + Source: [modules/events](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/events) @@ -683,8 +730,8 @@ It is currently only responsible for tone alarm on RC Loss. The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.). - -### Usage +### Usage {#send_event_usage} + ``` send_event [arguments...] Commands: @@ -694,7 +741,9 @@ send_event [arguments...] status print status info ``` + ## sensor_agp_sim + Source: [modules/simulation/sensor_agp_sim](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/sensor_agp_sim) @@ -702,8 +751,8 @@ Source: [modules/simulation/sensor_agp_sim](https://github.com/PX4/PX4-Autopilot Module to simulate auxiliary global position measurements with optional failure modes for SIH simulation. - -### Usage +### Usage {#sensor_agp_sim_usage} + ``` sensor_agp_sim [arguments...] Commands: @@ -713,7 +762,9 @@ sensor_agp_sim [arguments...] status print status info ``` + ## sensor_arispeed_sim + Source: [modules/simulation/sensor_airspeed_sim](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/sensor_airspeed_sim) @@ -721,8 +772,8 @@ Source: [modules/simulation/sensor_airspeed_sim](https://github.com/PX4/PX4-Auto - -### Usage +### Usage {#sensor_arispeed_sim_usage} + ``` sensor_arispeed_sim [arguments...] Commands: @@ -732,7 +783,9 @@ sensor_arispeed_sim [arguments...] status print status info ``` + ## sensor_baro_sim + Source: [modules/simulation/sensor_baro_sim](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/sensor_baro_sim) @@ -740,8 +793,8 @@ Source: [modules/simulation/sensor_baro_sim](https://github.com/PX4/PX4-Autopilo - -### Usage +### Usage {#sensor_baro_sim_usage} + ``` sensor_baro_sim [arguments...] Commands: @@ -751,7 +804,9 @@ sensor_baro_sim [arguments...] status print status info ``` + ## sensor_gps_sim + Source: [modules/simulation/sensor_gps_sim](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/sensor_gps_sim) @@ -759,8 +814,8 @@ Source: [modules/simulation/sensor_gps_sim](https://github.com/PX4/PX4-Autopilot - -### Usage +### Usage {#sensor_gps_sim_usage} + ``` sensor_gps_sim [arguments...] Commands: @@ -770,7 +825,9 @@ sensor_gps_sim [arguments...] status print status info ``` + ## sensor_mag_sim + Source: [modules/simulation/sensor_mag_sim](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/sensor_mag_sim) @@ -778,8 +835,8 @@ Source: [modules/simulation/sensor_mag_sim](https://github.com/PX4/PX4-Autopilot - -### Usage +### Usage {#sensor_mag_sim_usage} + ``` sensor_mag_sim [arguments...] Commands: @@ -789,7 +846,9 @@ sensor_mag_sim [arguments...] status print status info ``` + ## sensors + Source: [modules/sensors](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/sensors) @@ -811,8 +870,8 @@ The provided functionality includes: It runs in its own thread and polls on the currently selected gyro topic. - -### Usage +### Usage {#sensors_usage} + ``` sensors [arguments...] Commands: @@ -823,7 +882,9 @@ sensors [arguments...] status print status info ``` + ## system_power_simulation + Source: [modules/simulation/system_power_simulator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/system_power_simulator) @@ -831,8 +892,8 @@ Source: [modules/simulation/system_power_simulator](https://github.com/PX4/PX4-A - -### Usage +### Usage {#system_power_simulation_usage} + ``` system_power_simulation [arguments...] Commands: @@ -842,7 +903,9 @@ system_power_simulation [arguments...] status print status info ``` + ## tattu_can + Source: [drivers/tattu_can](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/tattu_can) @@ -850,8 +913,8 @@ Source: [drivers/tattu_can](https://github.com/PX4/PX4-Autopilot/tree/main/src/d Driver for reading data from the Tattu 12S 16000mAh smart battery. - -### Usage +### Usage {#tattu_can_usage} + ``` tattu_can [arguments...] Commands: @@ -861,7 +924,9 @@ tattu_can [arguments...] status print status info ``` + ## temperature_compensation + Source: [modules/temperature_compensation](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/temperature_compensation) @@ -873,8 +938,8 @@ routine at next boot, which allows the thermal calibration coeffecients to be ca a temperature cycle. - -### Usage +### Usage {#temperature_compensation_usage} + ``` temperature_compensation [arguments...] Commands: @@ -892,7 +957,9 @@ temperature_compensation [arguments...] status print status info ``` + ## time_persistor + Source: [modules/time_persistor](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/time_persistor) @@ -902,8 +969,8 @@ This allows monotonic time on systems that only have a software RTC (that is not Explicitly setting the time backwards (e.g. via system_time) is still possible. - -### Usage +### Usage {#time_persistor_usage} + ``` time_persistor [arguments...] Commands: @@ -913,7 +980,9 @@ time_persistor [arguments...] status print status info ``` + ## tune_control + Source: [systemcmds/tune_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/tune_control) @@ -934,8 +1003,8 @@ Play system tune #2: tune_control play -t 2 ``` - -### Usage +### Usage {#tune_control_usage} + ``` tune_control [arguments...] Commands: @@ -954,7 +1023,9 @@ tune_control [arguments...] stop Stop playback (use for repeated tunes) ``` + ## uxrce_dds_client + Source: [modules/uxrce_dds_client](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/uxrce_dds_client) @@ -967,8 +1038,8 @@ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600 uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555 ``` - -### Usage +### Usage {#uxrce_dds_client_usage} + ``` uxrce_dds_client [arguments...] Commands: @@ -989,7 +1060,9 @@ uxrce_dds_client [arguments...] status print status info ``` + ## work_queue + Source: [systemcmds/work_queue](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/work_queue) @@ -998,8 +1071,8 @@ Source: [systemcmds/work_queue](https://github.com/PX4/PX4-Autopilot/tree/main/s Command-line tool to show work queue status. - -### Usage +### Usage {#work_queue_usage} + ``` work_queue [arguments...] Commands: diff --git a/docs/en/modules/modules_template.md b/docs/en/modules/modules_template.md index 20f165cad5..523d9ff02b 100644 --- a/docs/en/modules/modules_template.md +++ b/docs/en/modules/modules_template.md @@ -1,6 +1,9 @@ # Modules Reference: Template + + ## module + Source: [templates/template_module](https://github.com/PX4/PX4-Autopilot/tree/main/src/templates/template_module) @@ -19,8 +22,8 @@ module start -f -p 42 ``` - -### Usage +### Usage {#module_usage} + ``` module [arguments...] Commands: @@ -33,7 +36,9 @@ module [arguments...] status print status info ``` + ## work_item_example + Source: [examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/work_item) @@ -41,8 +46,8 @@ Source: [examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/ Example of a simple module running out of a work queue. - -### Usage +### Usage {#work_item_example_usage} + ``` work_item_example [arguments...] Commands: diff --git a/docs/ko/_sidebar.md b/docs/ko/_sidebar.md index a90f9efdd4..13cd7d8dbb 100644 --- a/docs/ko/_sidebar.md +++ b/docs/ko/_sidebar.md @@ -42,8 +42,9 @@ - [마인드레이서 BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [마인드레이서 210](/complete_vehicles_mc/mindracer210.md) - [나노마인드 110](/complete_vehicles_mc/nanomind110.md) - - [홀리브로 코피스 2](/complete_vehicles_mc/holybro_kopis2.md) - [Bitcraze Crazyflie 2.1](/complete_vehicles_mc/crazyflie21.md) + - [홀리브로 코피스 2](/complete_vehicles_mc/holybro_kopis2.md) + - [Amov F410 Drone](/complete_vehicles_mc/amov_F410_drone.md) - [Kits](/frames_multicopter/kits.md) - [X500 v2 (Pixhawk 6C)](/frames_multicopter/holybro_x500v2_pixhawk6c.md) - [X500 v2 (Pixhawk 5X)](/frames_multicopter/holybro_x500V2_pixhawk5x.md) @@ -182,6 +183,7 @@ - [Holybro Kakute H7v2](/flight_controller/kakuteh7v2.md) - [Holybro Kakute H7mini](/flight_controller/kakuteh7mini.md) - [Holybro Kakute H7](/flight_controller/kakuteh7.md) + - [Holybro Kakute H7 Wing](/flight_controller/kakuteh7-wing.md) - [Holybro Durandal](/flight_controller/durandal.md) - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) @@ -253,6 +255,7 @@ - [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](/dronecan/avanon_laser_interface.md) - [GNSS (GPS)](/gps_compass/index.md) - [ARK GPS (CAN)](/dronecan/ark_gps.md) + - [ARK SAM GPS](/gps_compass/ark_sam_gps.md) - [ARK TESEO GPS](/dronecan/ark_teseo_gps.md) - [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md) - [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md) @@ -314,6 +317,7 @@ - [Joysticks](/config/joystick.md) - [Data Links](/data_links/index.md) - [MAVLink 텔레메트리(OSD/GCS) ](/peripherals/mavlink_peripherals.md) + - [텔레메트리 무선통신](/telemetry/index.md) - [SiK 무선통신](/telemetry/sik_radio.md) - [RFD900 (SiK) 텔레메트리](/telemetry/rfd900_telemetry.md) @@ -326,9 +330,13 @@ - [ARK Electron Microhard Serial Telemetry Radio](/telemetry/ark_microhard_serial.md) - [Holybro Microhard P900 Telemetry Radio](/telemetry/holybro_microhard_p900_radio.md) - [CUAV P8 Telemetry Radio](/telemetry/cuav_p8_radio.md) + - [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md) - [HolyBro XBP9X - Discontinued](/telemetry/holybro_xbp9x_radio.md) + - [FrSky 텔레메트리](/peripherals/frsky_telemetry.md) + - [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md) + - [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) - [Power Systems](/power_systems/index.md) - [Battery Estimation Tuning](/config/battery.md) @@ -637,6 +645,7 @@ - [PowerButtonState](/msg_docs/PowerButtonState.md) - [PowerMonitor](/msg_docs/PowerMonitor.md) - [PpsCapture](/msg_docs/PpsCapture.md) + - [PurePursuitStatus](/msg_docs/PurePursuitStatus.md) - [PwmInput](/msg_docs/PwmInput.md) - [Px4ioStatus](/msg_docs/Px4ioStatus.md) - [QshellReq](/msg_docs/QshellReq.md) @@ -710,6 +719,10 @@ - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](/middleware/mavlink.md) + - [Adding Messages](/mavlink/adding_messages.md) + - [Streaming Messages](/mavlink/streaming_messages.md) + - [Receiving Messages](/mavlink/receiving_messages.md) + - [Custom MAVLink Messages](/mavlink/custom_messages.md) - [Standard Modes Protocol](/mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md) - [모듈과 명령어](/modules/modules_main.md) @@ -798,8 +811,10 @@ - [시험 MC_05 - 실내 비행 (수동 모드)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [단위 테스트](/test_and_ci/unit_tests.md) - [지속 통합](/test_and_ci/continous_integration.md) - - [MAVSDK 통합 테스트](/test_and_ci/integration_testing_mavsdk.md) - - [ROS 통합 테스트](/test_and_ci/integration_testing.md) + - [Integration Testing](/test_and_ci/integration_testing.md) + - [MAVSDK 통합 테스트](/test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](/test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](/test_and_ci/integration_testing_ros1_mavros.md) - [도커 컨테이너](/test_and_ci/docker.md) - [유지보수](/test_and_ci/maintenance.md) @@ -840,4 +855,4 @@ - [1.15 (stable)](/releases/1.15.md) - [1.14](/releases/1.14.md) - [1.13](/releases/1.13.md) - - [1.12](/releases/1.12.md) \ No newline at end of file + - [1.12](/releases/1.12.md) diff --git a/docs/public/config/failsafe/index.js b/docs/public/config/failsafe/index.js index 44d21979f6..b557d6fc05 100644 --- a/docs/public/config/failsafe/index.js +++ b/docs/public/config/failsafe/index.js @@ -1 +1 @@ -var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof WorkerGlobalScope!="undefined";var ENVIRONMENT_IS_NODE=typeof process=="object"&&typeof process.versions=="object"&&typeof process.versions.node=="string"&&process.type!="renderer";if(ENVIRONMENT_IS_NODE){}var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var _scriptName=typeof document!="undefined"?document.currentScript?.src:undefined;if(typeof __filename!="undefined"){_scriptName=__filename}else if(ENVIRONMENT_IS_WORKER){_scriptName=self.location.href}var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");var nodePath=require("path");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename);return ret};readAsync=async(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename,binary?undefined:"utf8");return ret};if(process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){try{scriptDirectory=new URL(".",_scriptName).href}catch{}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=async url=>{if(isFileURI(url)){return new Promise((resolve,reject)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response);return}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}var response=await fetch(url,{credentials:"same-origin"});if(response.ok){return response.arrayBuffer()}throw new Error(response.status+" : "+response.url)}}}else{}var out=console.log.bind(console);var err=console.error.bind(console);var wasmBinary;var wasmMemory;var ABORT=false;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAP64,HEAPU64,HEAPF64;var runtimeInitialized=false;var isFileURI=filename=>filename.startsWith("file://");function updateMemoryViews(){var b=wasmMemory.buffer;HEAP8=new Int8Array(b);HEAP16=new Int16Array(b);HEAPU8=new Uint8Array(b);HEAPU16=new Uint16Array(b);HEAP32=new Int32Array(b);HEAPU32=new Uint32Array(b);HEAPF32=new Float32Array(b);HEAPF64=new Float64Array(b);HEAP64=new BigInt64Array(b);HEAPU64=new BigUint64Array(b)}function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(onPreRuns)}function initRuntime(){runtimeInitialized=true;wasmExports["v"]()}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(onPostRuns)}var runDependencies=0;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var wasmBinaryFile;function findWasmBinary(){return locateFile("index.wasm")}function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}async function getWasmBinary(binaryFile){if(!wasmBinary){try{var response=await readAsync(binaryFile);return new Uint8Array(response)}catch{}}return getBinarySync(binaryFile)}async function instantiateArrayBuffer(binaryFile,imports){try{var binary=await getWasmBinary(binaryFile);var instance=await WebAssembly.instantiate(binary,imports);return instance}catch(reason){err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)}}async function instantiateAsync(binary,binaryFile,imports){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE){try{var response=fetch(binaryFile,{credentials:"same-origin"});var instantiationResult=await WebAssembly.instantiateStreaming(response,imports);return instantiationResult}catch(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation")}}return instantiateArrayBuffer(binaryFile,imports)}function getWasmImports(){return{a:wasmImports}}async function createWasm(){function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["u"];updateMemoryViews();wasmTable=wasmExports["A"];removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){return receiveInstance(result["instance"])}var info=getWasmImports();if(Module["instantiateWasm"]){return new Promise((resolve,reject)=>{Module["instantiateWasm"](info,(mod,inst)=>{resolve(receiveInstance(mod,inst))})})}wasmBinaryFile??=findWasmBinary();var result=await instantiateAsync(wasmBinary,wasmBinaryFile,info);var exports=receiveInstantiationResult(result);return exports}class ExitStatus{name="ExitStatus";constructor(status){this.message=`Program terminated with exit(${status})`;this.status=status}}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var onPostRuns=[];var addOnPostRun=cb=>onPostRuns.push(cb);var onPreRuns=[];var addOnPreRun=cb=>onPreRuns.push(cb);var noExitRuntime=true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>abort("");var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};var embind_init_charCodes=()=>{var codes=new Array(256);for(var i=0;i<256;++i){codes[i]=String.fromCharCode(i)}embind_charCodes=codes};var embind_charCodes;var readLatin1String=ptr=>{var ret="";var c=ptr;while(HEAPU8[c]){ret+=embind_charCodes[HEAPU8[c++]]}return ret};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError=Module["BindingError"]=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};var throwBindingError=message=>{throw new BindingError(message)};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){return sharedRegisterType(rawType,registeredInstance,options)}var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];case 8:return signed?pointer=>HEAP64[pointer>>3]:pointer=>HEAPU64[pointer>>3];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);var isUnsignedType=name.indexOf("u")!=-1;if(isUnsignedType){maxRange=(1n<<64n)-1n}registerType(primitiveType,{name,fromWireType:value=>value,toWireType:function(destructors,value){if(typeof value!="bigint"&&typeof value!="number"){throw new TypeError(`Cannot convert "${embindRepr(value)}" to ${this.name}`)}if(typeof value=="number"){value=BigInt(value)}return value},argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,!isUnsignedType),destructorFunction:null})};var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var init_ClassHandle=()=>{let proto=ClassHandle.prototype;Object.assign(proto,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}});const symbolDispose=Symbol.dispose;if(symbolDispose){proto[symbolDispose]=proto["delete"]}};function ClassHandle(){}var createNamedFunction=(name,func)=>Object.defineProperty(func,"name",{value:name});var registeredPointers={};var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module[name].overloadTable.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var InternalError=Module["InternalError"]=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};var throwInternalError=message=>{throw new InternalError(message)};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var embind__requireFunction=(signature,rawFunction,isAsync=false)=>{signature=readLatin1String(signature);function makeDynCaller(){var rtn=getWasmTableEntry(rawFunction);return rtn}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};class UnboundTypeError extends Error{}var getTypeName=type=>{var ptr=___getTypeName(type);var rv=readLatin1String(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(type=>typeDependencies[type]=dependentTypes);function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=readLatin1String(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError(`Use 'new' to construct ${name}`)}if(undefined===registeredClass.constructor_body){throw new BindingError(`${name} has no accessible constructor`)}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex===-1)return signature;return signature.slice(0,argsIndex)};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync,isNonnullReturn)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=readLatin1String(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker,isAsync);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=readLatin1String(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var count_emval_handles=()=>emval_handles.length/2-5-emval_freelist.length;var init_emval=()=>{emval_handles.push(0,1,undefined,1,null,1,true,1,false,1);Module["count_emval_handles"]=count_emval_handles};var Emval={toValue:handle=>{if(!handle){throwBindingError(`Cannot use deleted val. handle = ${handle}`)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync,isNonnullReturn)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=readLatin1String(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker,isAsync);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);if(maxRange===-1){maxRange=4294967295}var fromWireType=value=>value;if(minRange===0){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift}var isUnsignedType=name.includes("unsigned");var checkAssertions=(value,toTypeName)=>{};var toWireType;if(isUnsignedType){toWireType=function(destructors,value){checkAssertions(value,this.name);return value>>>0}}else{toWireType=function(destructors,value){checkAssertions(value,this.name);return value}}registerType(primitiveType,{name,fromWireType,toWireType,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array,BigInt64Array,BigUint64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=readLatin1String(name);registerType(rawType,{name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=55296&&u<=57343){var u1=str.charCodeAt(++i);u=65536+((u&1023)<<10)|u1&1023}if(u<=127){if(outIdx>=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx=0,maxBytesToRead=NaN)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=readLatin1String(name);var stdStringIsUTF8=true;registerType(rawType,{name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(valueIsOfTypeString){if(stdStringIsUTF8){stringToUTF8(value,ptr,length+1)}else{for(var i=0;i255){_free(base);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}}else{HEAPU8.set(value,ptr)}if(destructors!==null){destructors.push(_free,base)}return base},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var UTF16Decoder=typeof TextDecoder!="undefined"?new TextDecoder("utf-16le"):undefined;var UTF16ToString=(ptr,maxBytesToRead)=>{var endPtr=ptr;var idx=endPtr>>1;var maxIdx=idx+maxBytesToRead/2;while(!(idx>=maxIdx)&&HEAPU16[idx])++idx;endPtr=idx<<1;if(endPtr-ptr>32&&UTF16Decoder)return UTF16Decoder.decode(HEAPU8.subarray(ptr,endPtr));var str="";for(var i=0;!(i>=maxBytesToRead/2);++i){var codeUnit=HEAP16[ptr+i*2>>1];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var i=0;var str="";while(!(i>=maxBytesToRead/4)){var utf32=HEAP32[ptr+i*4>>2];if(utf32==0)break;++i;if(utf32>=65536){var ch=utf32-65536;str+=String.fromCharCode(55296|ch>>10,56320|ch&1023)}else{str+=String.fromCharCode(utf32)}}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i=55296&&codeUnit<=57343){var trailSurrogate=str.charCodeAt(++i);codeUnit=65536+((codeUnit&1023)<<10)|trailSurrogate&1023}HEAP32[outPtr>>2]=codeUnit;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i=55296&&codeUnit<=57343)++i;len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=readLatin1String(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=readLatin1String(name);registerType(rawType,{isVoid:true,name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};embind_init_charCodes();init_ClassHandle();init_RegisteredPointer();init_emval();{if(Module["noExitRuntime"])noExitRuntime=Module["noExitRuntime"];if(Module["print"])out=Module["print"];if(Module["printErr"])err=Module["printErr"];if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"]}var wasmImports={f:___cxa_throw,p:__abort_js,k:__embind_register_bigint,m:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,r:__embind_register_emval,j:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,s:__embind_register_std_string,g:__embind_register_std_wstring,n:__embind_register_void,o:__emval_take_value,t:_emscripten_date_now,q:_emscripten_resize_heap,i:_fd_write};var wasmExports;createWasm();var ___wasm_call_ctors=()=>(___wasm_call_ctors=wasmExports["v"])();var _param_get=Module["_param_get"]=(a0,a1)=>(_param_get=Module["_param_get"]=wasmExports["w"])(a0,a1);var _param_set_used=Module["_param_set_used"]=a0=>(_param_set_used=Module["_param_set_used"]=wasmExports["x"])(a0);var __Znwm=Module["__Znwm"]=a0=>(__Znwm=Module["__Znwm"]=wasmExports["y"])(a0);var __ZdlPvm=Module["__ZdlPvm"]=(a0,a1)=>(__ZdlPvm=Module["__ZdlPvm"]=wasmExports["z"])(a0,a1);var _malloc=a0=>(_malloc=wasmExports["B"])(a0);var __ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=a0=>(__ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=wasmExports["C"])(a0);var ___cxa_allocate_exception=Module["___cxa_allocate_exception"]=a0=>(___cxa_allocate_exception=Module["___cxa_allocate_exception"]=wasmExports["D"])(a0);var __ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=a0=>(__ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=wasmExports["E"])(a0);var __ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=a0=>(__ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=wasmExports["F"])(a0);var __ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=a0=>(__ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=wasmExports["G"])(a0);var ___cxa_pure_virtual=Module["___cxa_pure_virtual"]=()=>(___cxa_pure_virtual=Module["___cxa_pure_virtual"]=wasmExports["H"])();var ___getTypeName=a0=>(___getTypeName=wasmExports["I"])(a0);var __ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=a0=>(__ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=wasmExports["J"])(a0);var __emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=(a0,a1,a2)=>(__emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=wasmExports["K"])(a0,a1,a2);var _emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=()=>(_emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=wasmExports["L"])();var _emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=()=>(_emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=wasmExports["M"])();var _free=a0=>(_free=wasmExports["N"])(a0);var _emscripten_stack_init=Module["_emscripten_stack_init"]=()=>(_emscripten_stack_init=Module["_emscripten_stack_init"]=wasmExports["O"])();var _emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=(a0,a1)=>(_emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=wasmExports["P"])(a0,a1);var _emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=()=>(_emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=wasmExports["Q"])();var __ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=()=>(__ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=wasmExports["R"])();var __Znam=Module["__Znam"]=a0=>(__Znam=Module["__Znam"]=wasmExports["S"])(a0);var __ZdlPv=Module["__ZdlPv"]=a0=>(__ZdlPv=Module["__ZdlPv"]=wasmExports["T"])(a0);var __ZdaPv=Module["__ZdaPv"]=a0=>(__ZdaPv=Module["__ZdaPv"]=wasmExports["U"])(a0);var __ZdaPvm=Module["__ZdaPvm"]=(a0,a1)=>(__ZdaPvm=Module["__ZdaPvm"]=wasmExports["V"])(a0,a1);var __ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=(a0,a1)=>(__ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=wasmExports["W"])(a0,a1);var __ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=(a0,a1)=>(__ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=wasmExports["X"])(a0,a1);var __ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=(a0,a1)=>(__ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=wasmExports["Y"])(a0,a1);var __ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=wasmExports["Z"])(a0,a1,a2);var __ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=(a0,a1)=>(__ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=wasmExports["_"])(a0,a1);var __ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=wasmExports["$"])(a0,a1,a2);var __ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=a0=>(__ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=wasmExports["aa"])(a0);var __ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=a0=>(__ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=wasmExports["ba"])(a0);var __ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=a0=>(__ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=wasmExports["ca"])(a0);var __ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=()=>(__ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=wasmExports["da"])();var __ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=()=>(__ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=wasmExports["ea"])();var __ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=()=>(__ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=wasmExports["fa"])();var __ZSt9terminatev=Module["__ZSt9terminatev"]=()=>(__ZSt9terminatev=Module["__ZSt9terminatev"]=wasmExports["ga"])();var ___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=()=>(___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=wasmExports["ha"])();var ___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=a0=>(___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=wasmExports["ia"])(a0);var ___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=()=>(___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=wasmExports["ja"])();var ___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=()=>(___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=wasmExports["ka"])();var ___cxa_free_exception=Module["___cxa_free_exception"]=a0=>(___cxa_free_exception=Module["___cxa_free_exception"]=wasmExports["la"])(a0);var ___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=(a0,a1,a2)=>(___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=wasmExports["ma"])(a0,a1,a2);var ___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=()=>(___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=wasmExports["na"])();var ___dynamic_cast=Module["___dynamic_cast"]=(a0,a1,a2,a3)=>(___dynamic_cast=Module["___dynamic_cast"]=wasmExports["oa"])(a0,a1,a2,a3);var __ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=a0=>(__ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=wasmExports["pa"])(a0);var __ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=a0=>(__ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=wasmExports["qa"])(a0);var __ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=a0=>(__ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=wasmExports["ra"])(a0);var __ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=a0=>(__ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=wasmExports["sa"])(a0);var __ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=a0=>(__ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=wasmExports["ta"])(a0);var __ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=a0=>(__ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=wasmExports["ua"])(a0);var __ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=a0=>(__ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=wasmExports["va"])(a0);var __ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=a0=>(__ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=wasmExports["wa"])(a0);var __ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=a0=>(__ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=wasmExports["xa"])(a0);var __ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=a0=>(__ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=wasmExports["ya"])(a0);var __ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=a0=>(__ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=wasmExports["za"])(a0);var __ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=a0=>(__ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=wasmExports["Aa"])(a0);var __ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=a0=>(__ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=wasmExports["Ba"])(a0);var __ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=a0=>(__ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=wasmExports["Ca"])(a0);var __ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=a0=>(__ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=wasmExports["Da"])(a0);var __ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=a0=>(__ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=wasmExports["Ea"])(a0);var __ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=a0=>(__ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=wasmExports["Fa"])(a0);var __ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=a0=>(__ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=wasmExports["Ga"])(a0);var __ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=a0=>(__ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=wasmExports["Ha"])(a0);var __ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=a0=>(__ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=wasmExports["Ia"])(a0);var __ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=a0=>(__ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=wasmExports["Ja"])(a0);var __ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=a0=>(__ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=wasmExports["Ka"])(a0);var __ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=a0=>(__ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=wasmExports["La"])(a0);var __ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=a0=>(__ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=wasmExports["Ma"])(a0);var __ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=a0=>(__ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=wasmExports["Na"])(a0);var __ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=a0=>(__ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=wasmExports["Oa"])(a0);var __ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=a0=>(__ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=wasmExports["Pa"])(a0);var __ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=a0=>(__ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=wasmExports["Qa"])(a0);var __ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=a0=>(__ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=wasmExports["Ra"])(a0);var __ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=a0=>(__ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=wasmExports["Sa"])(a0);var __ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=a0=>(__ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=wasmExports["Ta"])(a0);var __ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=a0=>(__ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=wasmExports["Ua"])(a0);var __ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=a0=>(__ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=wasmExports["Va"])(a0);var __ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=a0=>(__ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=wasmExports["Wa"])(a0);var __ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=a0=>(__ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=wasmExports["Xa"])(a0);var __ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=a0=>(__ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=wasmExports["Ya"])(a0);var __ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=a0=>(__ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=wasmExports["Za"])(a0);var __ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=a0=>(__ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=wasmExports["_a"])(a0);var __ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=a0=>(__ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=wasmExports["$a"])(a0);var __ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=a0=>(__ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=wasmExports["ab"])(a0);var __ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=a0=>(__ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=wasmExports["bb"])(a0);var __ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=a0=>(__ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=wasmExports["cb"])(a0);var __ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=a0=>(__ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=wasmExports["db"])(a0);var __ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=a0=>(__ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=wasmExports["eb"])(a0);var __ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=a0=>(__ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=wasmExports["fb"])(a0);var __ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=a0=>(__ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=wasmExports["gb"])(a0);var __ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=a0=>(__ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=wasmExports["hb"])(a0);var __ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=a0=>(__ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=wasmExports["ib"])(a0);var __ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=a0=>(__ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=wasmExports["jb"])(a0);var __ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=a0=>(__ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=wasmExports["kb"])(a0);var __ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=a0=>(__ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=wasmExports["lb"])(a0);var __ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=a0=>(__ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=wasmExports["mb"])(a0);var __ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=a0=>(__ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=wasmExports["nb"])(a0);var __ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=a0=>(__ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=wasmExports["ob"])(a0);var __ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=a0=>(__ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=wasmExports["pb"])(a0);var __ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=a0=>(__ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=wasmExports["qb"])(a0);var __ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=a0=>(__ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=wasmExports["rb"])(a0);var __ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=a0=>(__ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=wasmExports["sb"])(a0);var __ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=a0=>(__ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=wasmExports["tb"])(a0);var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=47504;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=47488;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=47480;var __ZTIb=Module["__ZTIb"]=30324;var __ZTIh=Module["__ZTIh"]=30480;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47660;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47644;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47592;var __ZTISt12length_error=Module["__ZTISt12length_error"]=32424;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=32404;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=32188;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=47580;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=32476;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=32456;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=31756;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=31848;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=31716;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28065;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=31968;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28084;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28104;var __ZTIi=Module["__ZTIi"]=30688;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28153;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28220;var __ZTIv=Module["__ZTIv"]=30216;var __ZTIf=Module["__ZTIf"]=31160;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28318;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28405;var __ZTIm=Module["__ZTIm"]=30844;var __ZTIN10emscripten3valE=Module["__ZTIN10emscripten3valE"]=47732;var __ZTSN10emscripten3valE=Module["__ZTSN10emscripten3valE"]=28508;var __ZTIc=Module["__ZTIc"]=30428;var __ZTIa=Module["__ZTIa"]=30532;var __ZTIs=Module["__ZTIs"]=30584;var __ZTIt=Module["__ZTIt"]=30636;var __ZTIj=Module["__ZTIj"]=30740;var __ZTIl=Module["__ZTIl"]=30792;var __ZTIx=Module["__ZTIx"]=30896;var __ZTIy=Module["__ZTIy"]=30948;var __ZTId=Module["__ZTId"]=31212;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28564;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28636;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28712;var __ZTIN10emscripten11memory_viewIcEE=Module["__ZTIN10emscripten11memory_viewIcEE"]=28788;var __ZTIN10emscripten11memory_viewIaEE=Module["__ZTIN10emscripten11memory_viewIaEE"]=28828;var __ZTIN10emscripten11memory_viewIhEE=Module["__ZTIN10emscripten11memory_viewIhEE"]=28868;var __ZTIN10emscripten11memory_viewIsEE=Module["__ZTIN10emscripten11memory_viewIsEE"]=28908;var __ZTIN10emscripten11memory_viewItEE=Module["__ZTIN10emscripten11memory_viewItEE"]=28948;var __ZTIN10emscripten11memory_viewIiEE=Module["__ZTIN10emscripten11memory_viewIiEE"]=28988;var __ZTIN10emscripten11memory_viewIjEE=Module["__ZTIN10emscripten11memory_viewIjEE"]=29028;var __ZTIN10emscripten11memory_viewIlEE=Module["__ZTIN10emscripten11memory_viewIlEE"]=29068;var __ZTIN10emscripten11memory_viewImEE=Module["__ZTIN10emscripten11memory_viewImEE"]=29108;var __ZTIN10emscripten11memory_viewIxEE=Module["__ZTIN10emscripten11memory_viewIxEE"]=29148;var __ZTIN10emscripten11memory_viewIyEE=Module["__ZTIN10emscripten11memory_viewIyEE"]=29188;var __ZTIN10emscripten11memory_viewIfEE=Module["__ZTIN10emscripten11memory_viewIfEE"]=29228;var __ZTIN10emscripten11memory_viewIdEE=Module["__ZTIN10emscripten11memory_viewIdEE"]=29268;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28572;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28644;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28720;var __ZTSN10emscripten11memory_viewIcEE=Module["__ZTSN10emscripten11memory_viewIcEE"]=28796;var __ZTSN10emscripten11memory_viewIaEE=Module["__ZTSN10emscripten11memory_viewIaEE"]=28836;var __ZTSN10emscripten11memory_viewIhEE=Module["__ZTSN10emscripten11memory_viewIhEE"]=28876;var __ZTSN10emscripten11memory_viewIsEE=Module["__ZTSN10emscripten11memory_viewIsEE"]=28916;var __ZTSN10emscripten11memory_viewItEE=Module["__ZTSN10emscripten11memory_viewItEE"]=28956;var __ZTSN10emscripten11memory_viewIiEE=Module["__ZTSN10emscripten11memory_viewIiEE"]=28996;var __ZTSN10emscripten11memory_viewIjEE=Module["__ZTSN10emscripten11memory_viewIjEE"]=29036;var __ZTSN10emscripten11memory_viewIlEE=Module["__ZTSN10emscripten11memory_viewIlEE"]=29076;var __ZTSN10emscripten11memory_viewImEE=Module["__ZTSN10emscripten11memory_viewImEE"]=29116;var __ZTSN10emscripten11memory_viewIxEE=Module["__ZTSN10emscripten11memory_viewIxEE"]=29156;var __ZTSN10emscripten11memory_viewIyEE=Module["__ZTSN10emscripten11memory_viewIyEE"]=29196;var __ZTSN10emscripten11memory_viewIfEE=Module["__ZTSN10emscripten11memory_viewIfEE"]=29236;var __ZTSN10emscripten11memory_viewIdEE=Module["__ZTSN10emscripten11memory_viewIdEE"]=29276;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=32228;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32064;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=32248;var __ZTISt9exception=Module["__ZTISt9exception"]=32084;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=47960;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=47956;var ___cxa_new_handler=Module["___cxa_new_handler"]=50204;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=29792;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=29840;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=29888;var __ZTIDn=Module["__ZTIDn"]=30268;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=29936;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=29984;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=30036;var __ZTISt9type_info=Module["__ZTISt9type_info"]=32748;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=29804;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=29852;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=29900;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=29948;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=29996;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=30048;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=30108;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=30136;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=30164;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=30176;var __ZTSv=Module["__ZTSv"]=30224;var __ZTIPv=Module["__ZTIPv"]=30228;var __ZTSPv=Module["__ZTSPv"]=30244;var __ZTIPKv=Module["__ZTIPKv"]=30248;var __ZTSPKv=Module["__ZTSPKv"]=30264;var __ZTSDn=Module["__ZTSDn"]=30276;var __ZTIPDn=Module["__ZTIPDn"]=30280;var __ZTSPDn=Module["__ZTSPDn"]=30296;var __ZTIPKDn=Module["__ZTIPKDn"]=30300;var __ZTSPKDn=Module["__ZTSPKDn"]=30316;var __ZTSb=Module["__ZTSb"]=30332;var __ZTIPb=Module["__ZTIPb"]=30336;var __ZTSPb=Module["__ZTSPb"]=30352;var __ZTIPKb=Module["__ZTIPKb"]=30356;var __ZTSPKb=Module["__ZTSPKb"]=30372;var __ZTIw=Module["__ZTIw"]=30376;var __ZTSw=Module["__ZTSw"]=30384;var __ZTIPw=Module["__ZTIPw"]=30388;var __ZTSPw=Module["__ZTSPw"]=30404;var __ZTIPKw=Module["__ZTIPKw"]=30408;var __ZTSPKw=Module["__ZTSPKw"]=30424;var __ZTSc=Module["__ZTSc"]=30436;var __ZTIPc=Module["__ZTIPc"]=30440;var __ZTSPc=Module["__ZTSPc"]=30456;var __ZTIPKc=Module["__ZTIPKc"]=30460;var __ZTSPKc=Module["__ZTSPKc"]=30476;var __ZTSh=Module["__ZTSh"]=30488;var __ZTIPh=Module["__ZTIPh"]=30492;var __ZTSPh=Module["__ZTSPh"]=30508;var __ZTIPKh=Module["__ZTIPKh"]=30512;var __ZTSPKh=Module["__ZTSPKh"]=30528;var __ZTSa=Module["__ZTSa"]=30540;var __ZTIPa=Module["__ZTIPa"]=30544;var __ZTSPa=Module["__ZTSPa"]=30560;var __ZTIPKa=Module["__ZTIPKa"]=30564;var __ZTSPKa=Module["__ZTSPKa"]=30580;var __ZTSs=Module["__ZTSs"]=30592;var __ZTIPs=Module["__ZTIPs"]=30596;var __ZTSPs=Module["__ZTSPs"]=30612;var __ZTIPKs=Module["__ZTIPKs"]=30616;var __ZTSPKs=Module["__ZTSPKs"]=30632;var __ZTSt=Module["__ZTSt"]=30644;var __ZTIPt=Module["__ZTIPt"]=30648;var __ZTSPt=Module["__ZTSPt"]=30664;var __ZTIPKt=Module["__ZTIPKt"]=30668;var __ZTSPKt=Module["__ZTSPKt"]=30684;var __ZTSi=Module["__ZTSi"]=30696;var __ZTIPi=Module["__ZTIPi"]=30700;var __ZTSPi=Module["__ZTSPi"]=30716;var __ZTIPKi=Module["__ZTIPKi"]=30720;var __ZTSPKi=Module["__ZTSPKi"]=30736;var __ZTSj=Module["__ZTSj"]=30748;var __ZTIPj=Module["__ZTIPj"]=30752;var __ZTSPj=Module["__ZTSPj"]=30768;var __ZTIPKj=Module["__ZTIPKj"]=30772;var __ZTSPKj=Module["__ZTSPKj"]=30788;var __ZTSl=Module["__ZTSl"]=30800;var __ZTIPl=Module["__ZTIPl"]=30804;var __ZTSPl=Module["__ZTSPl"]=30820;var __ZTIPKl=Module["__ZTIPKl"]=30824;var __ZTSPKl=Module["__ZTSPKl"]=30840;var __ZTSm=Module["__ZTSm"]=30852;var __ZTIPm=Module["__ZTIPm"]=30856;var __ZTSPm=Module["__ZTSPm"]=30872;var __ZTIPKm=Module["__ZTIPKm"]=30876;var __ZTSPKm=Module["__ZTSPKm"]=30892;var __ZTSx=Module["__ZTSx"]=30904;var __ZTIPx=Module["__ZTIPx"]=30908;var __ZTSPx=Module["__ZTSPx"]=30924;var __ZTIPKx=Module["__ZTIPKx"]=30928;var __ZTSPKx=Module["__ZTSPKx"]=30944;var __ZTSy=Module["__ZTSy"]=30956;var __ZTIPy=Module["__ZTIPy"]=30960;var __ZTSPy=Module["__ZTSPy"]=30976;var __ZTIPKy=Module["__ZTIPKy"]=30980;var __ZTSPKy=Module["__ZTSPKy"]=30996;var __ZTIn=Module["__ZTIn"]=31e3;var __ZTSn=Module["__ZTSn"]=31008;var __ZTIPn=Module["__ZTIPn"]=31012;var __ZTSPn=Module["__ZTSPn"]=31028;var __ZTIPKn=Module["__ZTIPKn"]=31032;var __ZTSPKn=Module["__ZTSPKn"]=31048;var __ZTIo=Module["__ZTIo"]=31052;var __ZTSo=Module["__ZTSo"]=31060;var __ZTIPo=Module["__ZTIPo"]=31064;var __ZTSPo=Module["__ZTSPo"]=31080;var __ZTIPKo=Module["__ZTIPKo"]=31084;var __ZTSPKo=Module["__ZTSPKo"]=31100;var __ZTIDh=Module["__ZTIDh"]=31104;var __ZTSDh=Module["__ZTSDh"]=31112;var __ZTIPDh=Module["__ZTIPDh"]=31116;var __ZTSPDh=Module["__ZTSPDh"]=31132;var __ZTIPKDh=Module["__ZTIPKDh"]=31136;var __ZTSPKDh=Module["__ZTSPKDh"]=31152;var __ZTSf=Module["__ZTSf"]=31168;var __ZTIPf=Module["__ZTIPf"]=31172;var __ZTSPf=Module["__ZTSPf"]=31188;var __ZTIPKf=Module["__ZTIPKf"]=31192;var __ZTSPKf=Module["__ZTSPKf"]=31208;var __ZTSd=Module["__ZTSd"]=31220;var __ZTIPd=Module["__ZTIPd"]=31224;var __ZTSPd=Module["__ZTSPd"]=31240;var __ZTIPKd=Module["__ZTIPKd"]=31244;var __ZTSPKd=Module["__ZTSPKd"]=31260;var __ZTIe=Module["__ZTIe"]=31264;var __ZTSe=Module["__ZTSe"]=31272;var __ZTIPe=Module["__ZTIPe"]=31276;var __ZTSPe=Module["__ZTSPe"]=31292;var __ZTIPKe=Module["__ZTIPKe"]=31296;var __ZTSPKe=Module["__ZTSPKe"]=31312;var __ZTIg=Module["__ZTIg"]=31316;var __ZTSg=Module["__ZTSg"]=31324;var __ZTIPg=Module["__ZTIPg"]=31328;var __ZTSPg=Module["__ZTSPg"]=31344;var __ZTIPKg=Module["__ZTIPKg"]=31348;var __ZTSPKg=Module["__ZTSPKg"]=31364;var __ZTIDu=Module["__ZTIDu"]=31368;var __ZTSDu=Module["__ZTSDu"]=31376;var __ZTIPDu=Module["__ZTIPDu"]=31380;var __ZTSPDu=Module["__ZTSPDu"]=31396;var __ZTIPKDu=Module["__ZTIPKDu"]=31400;var __ZTSPKDu=Module["__ZTSPKDu"]=31416;var __ZTIDs=Module["__ZTIDs"]=31424;var __ZTSDs=Module["__ZTSDs"]=31432;var __ZTIPDs=Module["__ZTIPDs"]=31436;var __ZTSPDs=Module["__ZTSPDs"]=31452;var __ZTIPKDs=Module["__ZTIPKDs"]=31456;var __ZTSPKDs=Module["__ZTSPKDs"]=31472;var __ZTIDi=Module["__ZTIDi"]=31480;var __ZTSDi=Module["__ZTSDi"]=31488;var __ZTIPDi=Module["__ZTIPDi"]=31492;var __ZTSPDi=Module["__ZTSPDi"]=31508;var __ZTIPKDi=Module["__ZTIPKDi"]=31512;var __ZTSPKDi=Module["__ZTSPKDi"]=31528;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=31536;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=31564;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=31576;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=31612;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=31640;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=31668;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=31680;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=31796;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=31808;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=31888;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=31900;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=31940;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=31996;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=32024;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=32044;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=32160;var __ZTSSt9exception=Module["__ZTSSt9exception"]=32092;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=32108;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=32128;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=32140;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=32172;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=32200;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=32320;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=32556;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=32268;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=32288;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=32300;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=32332;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=32348;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=32368;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=32380;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=32436;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=32488;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=32508;var __ZTISt11range_error=Module["__ZTISt11range_error"]=32528;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=32540;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=32568;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=32588;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=32608;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=32620;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=32640;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=32660;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=32672;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=32692;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=32712;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=32772;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=32796;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=32732;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=32756;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=32784;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=32808;function run(){if(runDependencies>0){dependenciesFulfilled=run;return}preRun();if(runDependencies>0){dependenciesFulfilled=run;return}function doRun(){Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(()=>{setTimeout(()=>Module["setStatus"](""),1);doRun()},1)}else{doRun()}}function preInit(){if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].shift()()}}}preInit();run(); +var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof WorkerGlobalScope!="undefined";var ENVIRONMENT_IS_NODE=typeof process=="object"&&process.versions?.node&&process.type!="renderer";if(ENVIRONMENT_IS_NODE){}var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var _scriptName=typeof document!="undefined"?document.currentScript?.src:undefined;if(typeof __filename!="undefined"){_scriptName=__filename}else if(ENVIRONMENT_IS_WORKER){_scriptName=self.location.href}var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");var nodePath=require("path");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename);return ret};readAsync=async(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename,binary?undefined:"utf8");return ret};if(process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){try{scriptDirectory=new URL(".",_scriptName).href}catch{}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=async url=>{if(isFileURI(url)){return new Promise((resolve,reject)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response);return}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}var response=await fetch(url,{credentials:"same-origin"});if(response.ok){return response.arrayBuffer()}throw new Error(response.status+" : "+response.url)}}}else{}var out=console.log.bind(console);var err=console.error.bind(console);var wasmBinary;var wasmMemory;var ABORT=false;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAP64,HEAPU64,HEAPF64;var runtimeInitialized=false;var isFileURI=filename=>filename.startsWith("file://");function updateMemoryViews(){var b=wasmMemory.buffer;HEAP8=new Int8Array(b);HEAP16=new Int16Array(b);HEAPU8=new Uint8Array(b);HEAPU16=new Uint16Array(b);HEAP32=new Int32Array(b);HEAPU32=new Uint32Array(b);HEAPF32=new Float32Array(b);HEAPF64=new Float64Array(b);HEAP64=new BigInt64Array(b);HEAPU64=new BigUint64Array(b)}function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(onPreRuns)}function initRuntime(){runtimeInitialized=true;wasmExports["v"]()}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(onPostRuns)}var runDependencies=0;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var wasmBinaryFile;function findWasmBinary(){return locateFile("index.wasm")}function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}async function getWasmBinary(binaryFile){if(!wasmBinary){try{var response=await readAsync(binaryFile);return new Uint8Array(response)}catch{}}return getBinarySync(binaryFile)}async function instantiateArrayBuffer(binaryFile,imports){try{var binary=await getWasmBinary(binaryFile);var instance=await WebAssembly.instantiate(binary,imports);return instance}catch(reason){err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)}}async function instantiateAsync(binary,binaryFile,imports){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE){try{var response=fetch(binaryFile,{credentials:"same-origin"});var instantiationResult=await WebAssembly.instantiateStreaming(response,imports);return instantiationResult}catch(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation")}}return instantiateArrayBuffer(binaryFile,imports)}function getWasmImports(){return{a:wasmImports}}async function createWasm(){function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["u"];updateMemoryViews();wasmTable=wasmExports["A"];removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){return receiveInstance(result["instance"])}var info=getWasmImports();if(Module["instantiateWasm"]){return new Promise((resolve,reject)=>{Module["instantiateWasm"](info,(mod,inst)=>{resolve(receiveInstance(mod,inst))})})}wasmBinaryFile??=findWasmBinary();var result=await instantiateAsync(wasmBinary,wasmBinaryFile,info);var exports=receiveInstantiationResult(result);return exports}class ExitStatus{name="ExitStatus";constructor(status){this.message=`Program terminated with exit(${status})`;this.status=status}}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var onPostRuns=[];var addOnPostRun=cb=>onPostRuns.push(cb);var onPreRuns=[];var addOnPreRun=cb=>onPreRuns.push(cb);var noExitRuntime=true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>abort("");var embind_init_charCodes=()=>{var codes=new Array(256);for(var i=0;i<256;++i){codes[i]=String.fromCharCode(i)}embind_charCodes=codes};var embind_charCodes;var readLatin1String=ptr=>{var ret="";var c=ptr;while(HEAPU8[c]){ret+=embind_charCodes[HEAPU8[c++]]}return ret};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};var throwBindingError=message=>{throw new BindingError(message)};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){return sharedRegisterType(rawType,registeredInstance,options)}var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];case 8:return signed?pointer=>HEAP64[pointer>>3]:pointer=>HEAPU64[pointer>>3];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);const isUnsignedType=minRange===0n;let fromWireType=value=>value;if(isUnsignedType){const bitSize=size*8;fromWireType=value=>BigInt.asUintN(bitSize,value);maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>{if(typeof value=="number"){value=BigInt(value)}return value},argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,!isUnsignedType),destructorFunction:null})};var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var init_ClassHandle=()=>{let proto=ClassHandle.prototype;Object.assign(proto,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}});const symbolDispose=Symbol.dispose;if(symbolDispose){proto[symbolDispose]=proto["delete"]}};function ClassHandle(){}var createNamedFunction=(name,func)=>Object.defineProperty(func,"name",{value:name});var registeredPointers={};var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module[name].overloadTable.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var InternalError=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};var throwInternalError=message=>{throw new InternalError(message)};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var embind__requireFunction=(signature,rawFunction,isAsync=false)=>{signature=readLatin1String(signature);function makeDynCaller(){var rtn=getWasmTableEntry(rawFunction);return rtn}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};class UnboundTypeError extends Error{}var getTypeName=type=>{var ptr=___getTypeName(type);var rv=readLatin1String(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(type=>typeDependencies[type]=dependentTypes);function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=readLatin1String(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError(`Use 'new' to construct ${name}`)}if(undefined===registeredClass.constructor_body){throw new BindingError(`${name} has no accessible constructor`)}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex===-1)return signature;return signature.slice(0,argsIndex)};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync,isNonnullReturn)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=readLatin1String(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker,isAsync);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=readLatin1String(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[0,1,,1,null,1,true,1,false,1];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var Emval={toValue:handle=>{if(!handle){throwBindingError(`Cannot use deleted val. handle = ${handle}`)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync,isNonnullReturn)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=readLatin1String(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker,isAsync);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);const isUnsignedType=minRange===0;let fromWireType=value=>value;if(isUnsignedType){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift;maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array,BigInt64Array,BigUint64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=readLatin1String(name);registerType(rawType,{name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=55296&&u<=57343){var u1=str.charCodeAt(++i);u=65536+((u&1023)<<10)|u1&1023}if(u<=127){if(outIdx>=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx=0,maxBytesToRead=NaN)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=readLatin1String(name);var stdStringIsUTF8=true;registerType(rawType,{name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(valueIsOfTypeString){if(stdStringIsUTF8){stringToUTF8(value,ptr,length+1)}else{for(var i=0;i255){_free(base);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}}else{HEAPU8.set(value,ptr)}if(destructors!==null){destructors.push(_free,base)}return base},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var UTF16Decoder=typeof TextDecoder!="undefined"?new TextDecoder("utf-16le"):undefined;var UTF16ToString=(ptr,maxBytesToRead)=>{var idx=ptr>>1;var maxIdx=idx+maxBytesToRead/2;var endIdx=idx;while(!(endIdx>=maxIdx)&&HEAPU16[endIdx])++endIdx;if(endIdx-idx>16&&UTF16Decoder)return UTF16Decoder.decode(HEAPU16.subarray(idx,endIdx));var str="";for(var i=idx;!(i>=maxIdx);++i){var codeUnit=HEAPU16[i];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var i=0;var str="";while(!(i>=maxBytesToRead/4)){var utf32=HEAP32[ptr+i*4>>2];if(utf32==0)break;++i;if(utf32>=65536){var ch=utf32-65536;str+=String.fromCharCode(55296|ch>>10,56320|ch&1023)}else{str+=String.fromCharCode(utf32)}}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i=55296&&codeUnit<=57343){var trailSurrogate=str.charCodeAt(++i);codeUnit=65536+((codeUnit&1023)<<10)|trailSurrogate&1023}HEAP32[outPtr>>2]=codeUnit;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i=55296&&codeUnit<=57343)++i;len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=readLatin1String(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=readLatin1String(name);registerType(rawType,{isVoid:true,name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};embind_init_charCodes();init_ClassHandle();init_RegisteredPointer();{if(Module["noExitRuntime"])noExitRuntime=Module["noExitRuntime"];if(Module["print"])out=Module["print"];if(Module["printErr"])err=Module["printErr"];if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"]}var wasmImports={f:___cxa_throw,p:__abort_js,k:__embind_register_bigint,m:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,r:__embind_register_emval,j:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,s:__embind_register_std_string,g:__embind_register_std_wstring,n:__embind_register_void,o:__emval_take_value,t:_emscripten_date_now,q:_emscripten_resize_heap,i:_fd_write};var wasmExports;createWasm();var ___wasm_call_ctors=()=>(___wasm_call_ctors=wasmExports["v"])();var _param_get=Module["_param_get"]=(a0,a1)=>(_param_get=Module["_param_get"]=wasmExports["w"])(a0,a1);var _param_set_used=Module["_param_set_used"]=a0=>(_param_set_used=Module["_param_set_used"]=wasmExports["x"])(a0);var __Znwm=Module["__Znwm"]=a0=>(__Znwm=Module["__Znwm"]=wasmExports["y"])(a0);var __ZdlPvm=Module["__ZdlPvm"]=(a0,a1)=>(__ZdlPvm=Module["__ZdlPvm"]=wasmExports["z"])(a0,a1);var _malloc=a0=>(_malloc=wasmExports["B"])(a0);var __ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=a0=>(__ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=wasmExports["C"])(a0);var ___cxa_allocate_exception=Module["___cxa_allocate_exception"]=a0=>(___cxa_allocate_exception=Module["___cxa_allocate_exception"]=wasmExports["D"])(a0);var __ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=a0=>(__ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=wasmExports["E"])(a0);var __ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=a0=>(__ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=wasmExports["F"])(a0);var __ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=a0=>(__ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=wasmExports["G"])(a0);var ___cxa_pure_virtual=Module["___cxa_pure_virtual"]=()=>(___cxa_pure_virtual=Module["___cxa_pure_virtual"]=wasmExports["H"])();var ___getTypeName=a0=>(___getTypeName=wasmExports["I"])(a0);var __ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=a0=>(__ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=wasmExports["J"])(a0);var __emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=(a0,a1,a2)=>(__emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=wasmExports["K"])(a0,a1,a2);var _emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=()=>(_emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=wasmExports["L"])();var _emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=()=>(_emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=wasmExports["M"])();var _free=a0=>(_free=wasmExports["N"])(a0);var _emscripten_stack_init=Module["_emscripten_stack_init"]=()=>(_emscripten_stack_init=Module["_emscripten_stack_init"]=wasmExports["O"])();var _emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=(a0,a1)=>(_emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=wasmExports["P"])(a0,a1);var _emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=()=>(_emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=wasmExports["Q"])();var __ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=()=>(__ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=wasmExports["R"])();var __Znam=Module["__Znam"]=a0=>(__Znam=Module["__Znam"]=wasmExports["S"])(a0);var __ZdlPv=Module["__ZdlPv"]=a0=>(__ZdlPv=Module["__ZdlPv"]=wasmExports["T"])(a0);var __ZdaPv=Module["__ZdaPv"]=a0=>(__ZdaPv=Module["__ZdaPv"]=wasmExports["U"])(a0);var __ZdaPvm=Module["__ZdaPvm"]=(a0,a1)=>(__ZdaPvm=Module["__ZdaPvm"]=wasmExports["V"])(a0,a1);var __ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=(a0,a1)=>(__ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=wasmExports["W"])(a0,a1);var __ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=(a0,a1)=>(__ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=wasmExports["X"])(a0,a1);var __ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=(a0,a1)=>(__ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=wasmExports["Y"])(a0,a1);var __ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=wasmExports["Z"])(a0,a1,a2);var __ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=(a0,a1)=>(__ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=wasmExports["_"])(a0,a1);var __ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=wasmExports["$"])(a0,a1,a2);var __ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=a0=>(__ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=wasmExports["aa"])(a0);var __ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=a0=>(__ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=wasmExports["ba"])(a0);var __ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=a0=>(__ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=wasmExports["ca"])(a0);var __ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=()=>(__ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=wasmExports["da"])();var __ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=()=>(__ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=wasmExports["ea"])();var __ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=()=>(__ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=wasmExports["fa"])();var __ZSt9terminatev=Module["__ZSt9terminatev"]=()=>(__ZSt9terminatev=Module["__ZSt9terminatev"]=wasmExports["ga"])();var ___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=()=>(___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=wasmExports["ha"])();var ___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=a0=>(___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=wasmExports["ia"])(a0);var ___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=()=>(___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=wasmExports["ja"])();var ___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=()=>(___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=wasmExports["ka"])();var ___cxa_free_exception=Module["___cxa_free_exception"]=a0=>(___cxa_free_exception=Module["___cxa_free_exception"]=wasmExports["la"])(a0);var ___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=(a0,a1,a2)=>(___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=wasmExports["ma"])(a0,a1,a2);var ___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=()=>(___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=wasmExports["na"])();var ___dynamic_cast=Module["___dynamic_cast"]=(a0,a1,a2,a3)=>(___dynamic_cast=Module["___dynamic_cast"]=wasmExports["oa"])(a0,a1,a2,a3);var __ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=a0=>(__ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=wasmExports["pa"])(a0);var __ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=a0=>(__ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=wasmExports["qa"])(a0);var __ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=a0=>(__ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=wasmExports["ra"])(a0);var __ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=a0=>(__ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=wasmExports["sa"])(a0);var __ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=a0=>(__ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=wasmExports["ta"])(a0);var __ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=a0=>(__ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=wasmExports["ua"])(a0);var __ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=a0=>(__ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=wasmExports["va"])(a0);var __ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=a0=>(__ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=wasmExports["wa"])(a0);var __ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=a0=>(__ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=wasmExports["xa"])(a0);var __ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=a0=>(__ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=wasmExports["ya"])(a0);var __ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=a0=>(__ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=wasmExports["za"])(a0);var __ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=a0=>(__ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=wasmExports["Aa"])(a0);var __ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=a0=>(__ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=wasmExports["Ba"])(a0);var __ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=a0=>(__ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=wasmExports["Ca"])(a0);var __ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=a0=>(__ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=wasmExports["Da"])(a0);var __ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=a0=>(__ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=wasmExports["Ea"])(a0);var __ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=a0=>(__ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=wasmExports["Fa"])(a0);var __ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=a0=>(__ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=wasmExports["Ga"])(a0);var __ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=a0=>(__ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=wasmExports["Ha"])(a0);var __ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=a0=>(__ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=wasmExports["Ia"])(a0);var __ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=a0=>(__ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=wasmExports["Ja"])(a0);var __ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=a0=>(__ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=wasmExports["Ka"])(a0);var __ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=a0=>(__ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=wasmExports["La"])(a0);var __ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=a0=>(__ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=wasmExports["Ma"])(a0);var __ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=a0=>(__ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=wasmExports["Na"])(a0);var __ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=a0=>(__ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=wasmExports["Oa"])(a0);var __ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=a0=>(__ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=wasmExports["Pa"])(a0);var __ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=a0=>(__ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=wasmExports["Qa"])(a0);var __ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=a0=>(__ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=wasmExports["Ra"])(a0);var __ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=a0=>(__ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=wasmExports["Sa"])(a0);var __ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=a0=>(__ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=wasmExports["Ta"])(a0);var __ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=a0=>(__ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=wasmExports["Ua"])(a0);var __ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=a0=>(__ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=wasmExports["Va"])(a0);var __ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=a0=>(__ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=wasmExports["Wa"])(a0);var __ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=a0=>(__ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=wasmExports["Xa"])(a0);var __ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=a0=>(__ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=wasmExports["Ya"])(a0);var __ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=a0=>(__ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=wasmExports["Za"])(a0);var __ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=a0=>(__ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=wasmExports["_a"])(a0);var __ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=a0=>(__ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=wasmExports["$a"])(a0);var __ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=a0=>(__ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=wasmExports["ab"])(a0);var __ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=a0=>(__ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=wasmExports["bb"])(a0);var __ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=a0=>(__ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=wasmExports["cb"])(a0);var __ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=a0=>(__ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=wasmExports["db"])(a0);var __ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=a0=>(__ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=wasmExports["eb"])(a0);var __ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=a0=>(__ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=wasmExports["fb"])(a0);var __ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=a0=>(__ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=wasmExports["gb"])(a0);var __ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=a0=>(__ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=wasmExports["hb"])(a0);var __ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=a0=>(__ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=wasmExports["ib"])(a0);var __ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=a0=>(__ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=wasmExports["jb"])(a0);var __ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=a0=>(__ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=wasmExports["kb"])(a0);var __ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=a0=>(__ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=wasmExports["lb"])(a0);var __ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=a0=>(__ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=wasmExports["mb"])(a0);var __ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=a0=>(__ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=wasmExports["nb"])(a0);var __ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=a0=>(__ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=wasmExports["ob"])(a0);var __ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=a0=>(__ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=wasmExports["pb"])(a0);var __ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=a0=>(__ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=wasmExports["qb"])(a0);var __ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=a0=>(__ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=wasmExports["rb"])(a0);var __ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=a0=>(__ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=wasmExports["sb"])(a0);var __ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=a0=>(__ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=wasmExports["tb"])(a0);var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=47520;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=47504;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=47496;var __ZTIb=Module["__ZTIb"]=30340;var __ZTIh=Module["__ZTIh"]=30496;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47676;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47660;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47608;var __ZTISt12length_error=Module["__ZTISt12length_error"]=32440;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=32420;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=32204;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=47596;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=32492;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=32472;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=31772;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=31864;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=31732;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28075;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=31984;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28094;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28114;var __ZTIi=Module["__ZTIi"]=30704;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28163;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28230;var __ZTIv=Module["__ZTIv"]=30232;var __ZTIf=Module["__ZTIf"]=31176;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28328;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28415;var __ZTIm=Module["__ZTIm"]=30860;var __ZTIN10emscripten3valE=Module["__ZTIN10emscripten3valE"]=47748;var __ZTSN10emscripten3valE=Module["__ZTSN10emscripten3valE"]=28518;var __ZTIc=Module["__ZTIc"]=30444;var __ZTIa=Module["__ZTIa"]=30548;var __ZTIs=Module["__ZTIs"]=30600;var __ZTIt=Module["__ZTIt"]=30652;var __ZTIj=Module["__ZTIj"]=30756;var __ZTIl=Module["__ZTIl"]=30808;var __ZTIx=Module["__ZTIx"]=30912;var __ZTIy=Module["__ZTIy"]=30964;var __ZTId=Module["__ZTId"]=31228;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28572;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28644;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28720;var __ZTIN10emscripten11memory_viewIcEE=Module["__ZTIN10emscripten11memory_viewIcEE"]=28796;var __ZTIN10emscripten11memory_viewIaEE=Module["__ZTIN10emscripten11memory_viewIaEE"]=28836;var __ZTIN10emscripten11memory_viewIhEE=Module["__ZTIN10emscripten11memory_viewIhEE"]=28876;var __ZTIN10emscripten11memory_viewIsEE=Module["__ZTIN10emscripten11memory_viewIsEE"]=28916;var __ZTIN10emscripten11memory_viewItEE=Module["__ZTIN10emscripten11memory_viewItEE"]=28956;var __ZTIN10emscripten11memory_viewIiEE=Module["__ZTIN10emscripten11memory_viewIiEE"]=28996;var __ZTIN10emscripten11memory_viewIjEE=Module["__ZTIN10emscripten11memory_viewIjEE"]=29036;var __ZTIN10emscripten11memory_viewIlEE=Module["__ZTIN10emscripten11memory_viewIlEE"]=29076;var __ZTIN10emscripten11memory_viewImEE=Module["__ZTIN10emscripten11memory_viewImEE"]=29116;var __ZTIN10emscripten11memory_viewIxEE=Module["__ZTIN10emscripten11memory_viewIxEE"]=29156;var __ZTIN10emscripten11memory_viewIyEE=Module["__ZTIN10emscripten11memory_viewIyEE"]=29196;var __ZTIN10emscripten11memory_viewIfEE=Module["__ZTIN10emscripten11memory_viewIfEE"]=29236;var __ZTIN10emscripten11memory_viewIdEE=Module["__ZTIN10emscripten11memory_viewIdEE"]=29276;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28580;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28652;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28728;var __ZTSN10emscripten11memory_viewIcEE=Module["__ZTSN10emscripten11memory_viewIcEE"]=28804;var __ZTSN10emscripten11memory_viewIaEE=Module["__ZTSN10emscripten11memory_viewIaEE"]=28844;var __ZTSN10emscripten11memory_viewIhEE=Module["__ZTSN10emscripten11memory_viewIhEE"]=28884;var __ZTSN10emscripten11memory_viewIsEE=Module["__ZTSN10emscripten11memory_viewIsEE"]=28924;var __ZTSN10emscripten11memory_viewItEE=Module["__ZTSN10emscripten11memory_viewItEE"]=28964;var __ZTSN10emscripten11memory_viewIiEE=Module["__ZTSN10emscripten11memory_viewIiEE"]=29004;var __ZTSN10emscripten11memory_viewIjEE=Module["__ZTSN10emscripten11memory_viewIjEE"]=29044;var __ZTSN10emscripten11memory_viewIlEE=Module["__ZTSN10emscripten11memory_viewIlEE"]=29084;var __ZTSN10emscripten11memory_viewImEE=Module["__ZTSN10emscripten11memory_viewImEE"]=29124;var __ZTSN10emscripten11memory_viewIxEE=Module["__ZTSN10emscripten11memory_viewIxEE"]=29164;var __ZTSN10emscripten11memory_viewIyEE=Module["__ZTSN10emscripten11memory_viewIyEE"]=29204;var __ZTSN10emscripten11memory_viewIfEE=Module["__ZTSN10emscripten11memory_viewIfEE"]=29244;var __ZTSN10emscripten11memory_viewIdEE=Module["__ZTSN10emscripten11memory_viewIdEE"]=29284;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=32244;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32080;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=32264;var __ZTISt9exception=Module["__ZTISt9exception"]=32100;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=47976;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=47972;var ___cxa_new_handler=Module["___cxa_new_handler"]=50220;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=29808;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=29856;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=29904;var __ZTIDn=Module["__ZTIDn"]=30284;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=29952;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=3e4;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=30052;var __ZTISt9type_info=Module["__ZTISt9type_info"]=32764;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=29820;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=29868;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=29916;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=29964;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=30012;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=30064;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=30124;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=30152;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=30180;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=30192;var __ZTSv=Module["__ZTSv"]=30240;var __ZTIPv=Module["__ZTIPv"]=30244;var __ZTSPv=Module["__ZTSPv"]=30260;var __ZTIPKv=Module["__ZTIPKv"]=30264;var __ZTSPKv=Module["__ZTSPKv"]=30280;var __ZTSDn=Module["__ZTSDn"]=30292;var __ZTIPDn=Module["__ZTIPDn"]=30296;var __ZTSPDn=Module["__ZTSPDn"]=30312;var __ZTIPKDn=Module["__ZTIPKDn"]=30316;var __ZTSPKDn=Module["__ZTSPKDn"]=30332;var __ZTSb=Module["__ZTSb"]=30348;var __ZTIPb=Module["__ZTIPb"]=30352;var __ZTSPb=Module["__ZTSPb"]=30368;var __ZTIPKb=Module["__ZTIPKb"]=30372;var __ZTSPKb=Module["__ZTSPKb"]=30388;var __ZTIw=Module["__ZTIw"]=30392;var __ZTSw=Module["__ZTSw"]=30400;var __ZTIPw=Module["__ZTIPw"]=30404;var __ZTSPw=Module["__ZTSPw"]=30420;var __ZTIPKw=Module["__ZTIPKw"]=30424;var __ZTSPKw=Module["__ZTSPKw"]=30440;var __ZTSc=Module["__ZTSc"]=30452;var __ZTIPc=Module["__ZTIPc"]=30456;var __ZTSPc=Module["__ZTSPc"]=30472;var __ZTIPKc=Module["__ZTIPKc"]=30476;var __ZTSPKc=Module["__ZTSPKc"]=30492;var __ZTSh=Module["__ZTSh"]=30504;var __ZTIPh=Module["__ZTIPh"]=30508;var __ZTSPh=Module["__ZTSPh"]=30524;var __ZTIPKh=Module["__ZTIPKh"]=30528;var __ZTSPKh=Module["__ZTSPKh"]=30544;var __ZTSa=Module["__ZTSa"]=30556;var __ZTIPa=Module["__ZTIPa"]=30560;var __ZTSPa=Module["__ZTSPa"]=30576;var __ZTIPKa=Module["__ZTIPKa"]=30580;var __ZTSPKa=Module["__ZTSPKa"]=30596;var __ZTSs=Module["__ZTSs"]=30608;var __ZTIPs=Module["__ZTIPs"]=30612;var __ZTSPs=Module["__ZTSPs"]=30628;var __ZTIPKs=Module["__ZTIPKs"]=30632;var __ZTSPKs=Module["__ZTSPKs"]=30648;var __ZTSt=Module["__ZTSt"]=30660;var __ZTIPt=Module["__ZTIPt"]=30664;var __ZTSPt=Module["__ZTSPt"]=30680;var __ZTIPKt=Module["__ZTIPKt"]=30684;var __ZTSPKt=Module["__ZTSPKt"]=30700;var __ZTSi=Module["__ZTSi"]=30712;var __ZTIPi=Module["__ZTIPi"]=30716;var __ZTSPi=Module["__ZTSPi"]=30732;var __ZTIPKi=Module["__ZTIPKi"]=30736;var __ZTSPKi=Module["__ZTSPKi"]=30752;var __ZTSj=Module["__ZTSj"]=30764;var __ZTIPj=Module["__ZTIPj"]=30768;var __ZTSPj=Module["__ZTSPj"]=30784;var __ZTIPKj=Module["__ZTIPKj"]=30788;var __ZTSPKj=Module["__ZTSPKj"]=30804;var __ZTSl=Module["__ZTSl"]=30816;var __ZTIPl=Module["__ZTIPl"]=30820;var __ZTSPl=Module["__ZTSPl"]=30836;var __ZTIPKl=Module["__ZTIPKl"]=30840;var __ZTSPKl=Module["__ZTSPKl"]=30856;var __ZTSm=Module["__ZTSm"]=30868;var __ZTIPm=Module["__ZTIPm"]=30872;var __ZTSPm=Module["__ZTSPm"]=30888;var __ZTIPKm=Module["__ZTIPKm"]=30892;var __ZTSPKm=Module["__ZTSPKm"]=30908;var __ZTSx=Module["__ZTSx"]=30920;var __ZTIPx=Module["__ZTIPx"]=30924;var __ZTSPx=Module["__ZTSPx"]=30940;var __ZTIPKx=Module["__ZTIPKx"]=30944;var __ZTSPKx=Module["__ZTSPKx"]=30960;var __ZTSy=Module["__ZTSy"]=30972;var __ZTIPy=Module["__ZTIPy"]=30976;var __ZTSPy=Module["__ZTSPy"]=30992;var __ZTIPKy=Module["__ZTIPKy"]=30996;var __ZTSPKy=Module["__ZTSPKy"]=31012;var __ZTIn=Module["__ZTIn"]=31016;var __ZTSn=Module["__ZTSn"]=31024;var __ZTIPn=Module["__ZTIPn"]=31028;var __ZTSPn=Module["__ZTSPn"]=31044;var __ZTIPKn=Module["__ZTIPKn"]=31048;var __ZTSPKn=Module["__ZTSPKn"]=31064;var __ZTIo=Module["__ZTIo"]=31068;var __ZTSo=Module["__ZTSo"]=31076;var __ZTIPo=Module["__ZTIPo"]=31080;var __ZTSPo=Module["__ZTSPo"]=31096;var __ZTIPKo=Module["__ZTIPKo"]=31100;var __ZTSPKo=Module["__ZTSPKo"]=31116;var __ZTIDh=Module["__ZTIDh"]=31120;var __ZTSDh=Module["__ZTSDh"]=31128;var __ZTIPDh=Module["__ZTIPDh"]=31132;var __ZTSPDh=Module["__ZTSPDh"]=31148;var __ZTIPKDh=Module["__ZTIPKDh"]=31152;var __ZTSPKDh=Module["__ZTSPKDh"]=31168;var __ZTSf=Module["__ZTSf"]=31184;var __ZTIPf=Module["__ZTIPf"]=31188;var __ZTSPf=Module["__ZTSPf"]=31204;var __ZTIPKf=Module["__ZTIPKf"]=31208;var __ZTSPKf=Module["__ZTSPKf"]=31224;var __ZTSd=Module["__ZTSd"]=31236;var __ZTIPd=Module["__ZTIPd"]=31240;var __ZTSPd=Module["__ZTSPd"]=31256;var __ZTIPKd=Module["__ZTIPKd"]=31260;var __ZTSPKd=Module["__ZTSPKd"]=31276;var __ZTIe=Module["__ZTIe"]=31280;var __ZTSe=Module["__ZTSe"]=31288;var __ZTIPe=Module["__ZTIPe"]=31292;var __ZTSPe=Module["__ZTSPe"]=31308;var __ZTIPKe=Module["__ZTIPKe"]=31312;var __ZTSPKe=Module["__ZTSPKe"]=31328;var __ZTIg=Module["__ZTIg"]=31332;var __ZTSg=Module["__ZTSg"]=31340;var __ZTIPg=Module["__ZTIPg"]=31344;var __ZTSPg=Module["__ZTSPg"]=31360;var __ZTIPKg=Module["__ZTIPKg"]=31364;var __ZTSPKg=Module["__ZTSPKg"]=31380;var __ZTIDu=Module["__ZTIDu"]=31384;var __ZTSDu=Module["__ZTSDu"]=31392;var __ZTIPDu=Module["__ZTIPDu"]=31396;var __ZTSPDu=Module["__ZTSPDu"]=31412;var __ZTIPKDu=Module["__ZTIPKDu"]=31416;var __ZTSPKDu=Module["__ZTSPKDu"]=31432;var __ZTIDs=Module["__ZTIDs"]=31440;var __ZTSDs=Module["__ZTSDs"]=31448;var __ZTIPDs=Module["__ZTIPDs"]=31452;var __ZTSPDs=Module["__ZTSPDs"]=31468;var __ZTIPKDs=Module["__ZTIPKDs"]=31472;var __ZTSPKDs=Module["__ZTSPKDs"]=31488;var __ZTIDi=Module["__ZTIDi"]=31496;var __ZTSDi=Module["__ZTSDi"]=31504;var __ZTIPDi=Module["__ZTIPDi"]=31508;var __ZTSPDi=Module["__ZTSPDi"]=31524;var __ZTIPKDi=Module["__ZTIPKDi"]=31528;var __ZTSPKDi=Module["__ZTSPKDi"]=31544;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=31552;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=31580;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=31592;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=31628;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=31656;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=31684;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=31696;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=31812;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=31824;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=31904;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=31916;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=31956;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=32012;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=32040;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=32060;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=32176;var __ZTSSt9exception=Module["__ZTSSt9exception"]=32108;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=32124;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=32144;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=32156;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=32188;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=32216;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=32336;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=32572;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=32284;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=32304;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=32316;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=32348;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=32364;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=32384;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=32396;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=32452;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=32504;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=32524;var __ZTISt11range_error=Module["__ZTISt11range_error"]=32544;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=32556;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=32584;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=32604;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=32624;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=32636;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=32656;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=32676;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=32688;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=32708;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=32728;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=32788;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=32812;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=32748;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=32772;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=32800;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=32824;function run(){if(runDependencies>0){dependenciesFulfilled=run;return}preRun();if(runDependencies>0){dependenciesFulfilled=run;return}function doRun(){Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(()=>{setTimeout(()=>Module["setStatus"](""),1);doRun()},1)}else{doRun()}}function preInit(){if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].shift()()}}}preInit();run(); diff --git a/docs/public/config/failsafe/index.wasm b/docs/public/config/failsafe/index.wasm index 67d8c55687a35e72b1e7f715689fce0b077ca186..decc623efa0ca9bc62eeabb4a58a2085dd9eeb61 100644 GIT binary patch delta 27921 zcma)l34ByV@_+T4$vFuO_YsblfE*GaT;WXSbx1%7AeSP7A_xLOIV2o%&7e_0aRnZ0 zP+1%f6<5S)Z~-|I-KfzYYCHi22`j6tqQnKcMEQTJ`a6hh{CxiTe57AjSADCxySlo% z-^}>Ws;K={QAP2VDk}C_?^&vW`?+^QaNSv}jYXPn&=o&h{9hZ3Qlj+Onduf;LCdim z9TJutuRQ4rO1DU#{Mpj-Q2Dc!McqB5FNtWfhaYS!-J%5Ly zYq-C_)5fA36O~Q2H!qpEFP5V#+>fJMMeQl@=soVQ(d$&1`&7)p<|iNayk~%TM9{C3|H;gWM&yC0Z+6<)>J}R_Z?E+ZT1Xz@rbl z;}b5b1McmKt<|IMLy4`_Gw#+zM?LEPkeI9vxHW5ZSI@ZpYow}2-TWF%d7?%~^^E(r zP)-Y_UQMRt)J$#h=mBL%=?azSuj{i(Q!g5opnP_eO>L|(=~k)I2i!HnT~?D3f2zrd zb^I*f*WXS(>Q49D>VUh_-(EfA?(<)-9(DiYPgVzteYNT<^^==YJ5BviJiK;CmAa30 zv7RU$_T;rB+vEE*T1AT&TaGR`C(dno`O)20r=wMH&OKVEo(j7^*BO!!e!$9WV|kOK zxpipW&MiX1&m*PS_s_v87$ljvGX>|0pR3!>ie7fk(#y^jAE^JF)$P(R;yI+fdH$g` z`RbBQdgY}*5`AQoziDHe{PlgYq~CL2ZPZ=ualdQSrwLDI3fW4ZEb!!s?lx9ziul|f zH>>d=Rpzd2oNCxCo360YRcr?v-`YalLc#6WKWui4SaA#w9AkJ=pEm4?F}%LY3Osfc zFI%54;vl}9L}mLXYb#%$bay0GsZw`KlN;1Y_opT=tCQ}ArZ=lH_gvFQ6U&T4MGf-u z`g*+CxC}<)K8vSwG_Xm><|R`?oX?KtMZ;aQZuC0*Y+H8p)D&U=w7{c3b=x=Z9bB`F zdAyEZCl4G=!pl5a!R{96waYwNp>QY^3VFG@W|_y1*9m!g#!P+i@1OlWY8GqWvJ9*6 z{8BuGY+s7XOYv&5)zp-jnJLPS9+ViX&ny*lqP&hiX&z&3_uJ-mlg}^pv?tPD9xoF< zELr+&Jab=io7lb8TK87FeF8w(;*;(wdz@P5p0>M0vGVh7yX4I7CzpBvZ+r7nBzRVd zHk)`Hs+M|eCi;F?;Sm+#^zO>YkHLv9$ zQz{EQJVb3Q(YXx6;&C`k_8kkm3wt3Y>R_* zl)mI?9Cw0P&I?yeRQl}B5&PcK;JX=_n;%Wo_0u{_7>f@L0C>DWB( z_5TjYvSn^o%klBDGKd4FyRBt?wZ|RTuCaTx<#1bKq>@bn5i*KnX?}{#zbUZ39S-qvd9P1rNM|GQ_HL5MM)V0(C=?@PD5?B`~$FhbYt6c=0F zid|x4>z(SP>u=L2%Ir`b+Pq};0_mDrU`i`HMwYw@@{zv!+~l@HOn+rtjP#fJt^AZI z>z5}`%s;9OHv!DQuk2m z+a_*F*x)d$tl*WX6=R!u*yFz0zFRzx3p=YWD^?vASgO)pl-8}r&H|54V`{LbPglC7 zX>E|;G`1WoXp{fC6lF8$m9)p}*zE9}oOI=l=}N_yLj4k{u}wZ(^-mfUP7pcLf|+A0c(kOfg+1WPfn*;ph=!| z%{;C2nc`16b+y#r-Po?dCI>HKk12{gltmu)7jNp?Te&UL+r`b$dk-pJ;O@xuK5=)V zR_U%w@8cVSS_S2~|4Q!_@1X8Xbz61s6_HMZ+kL5f@0&}}!R|mOwPoB3po~oINq*uwaP5l$eRuaezhQF>}SA4pAGZj^JLg@;(e$Vyl zxcgeq0jgqkuanWr*(Ba;w{{hpAv)h`FduBRdC5&5%@~&ES~DbM5zypXXX5=RAuqZ{$D9; z>F32mZ@k%~b{0QBaGMoeds68Yet)7a_(ACd30i6LC+L$uDE*{QD;)~z%jEayPk&T; z_0@#%k4mp(0_n@j@6pRnDZMXFTRIe4tS<{`&ncx}V-o4hmpy)ut~#ak`*GTpZu57QF>)?4>PU#nj78~pgmu6!?*Hm6r2?vqu?`nHVSs` z{awKm@@y3B6C;d*b@F`tYo%lLFT%6pxYBX@kUVcc-d^cw{SN^>d|c@m{kKx(SH5PX zWBr|M^52<4dh4$UB0Js1LsQe2owoGK)0PgO=9&HWOYZA;U-C$pe|OZ-C%;tM^;LdxwNqaz9nI2wX2bwjK+&Ks%hMS#z(5t`2`yPTODkjTa3;F)in-8V@Y+^K7_^-)fu!8jW1MZ z&^a{jt*$X`q%r6#Up4)lGBP>HQ+A*lomb}iofFVWksvBFGQL^9Ik$=}V<+=$asJeve~J=!~Tq*sp7Wekd5HJ$l6%ORqbkbZuP+ z^w;0xHM{nVCEie1*8}|&2kY<|OK&)$bbZ|bDhUux{XStIqh`9fKSsxj`%}8*wMpBY zw=v}51ntokXDofdJ$!3&Z6-ZkLwj}Q8A~7jO6eAE<*g0tw2ZL-t%kOA)fr3w%k4F) z@nB~Ej0fZV8B1UIO6k^o?I0F=vEJH5L_gx4XywnA{_QKJ+y2hy8>u*3)CCW?&F0*c z?jiC;k=|CzSDz0=S2C^2%O+ZK-`3^&ZxVdX{~+@}*%=EzT*uedo%~pr zp4VVRn3?CSkN;hs;5(ymrNLJcd=mBWg+Hm4mD=j&j_c!t zGK-b19v4ty_v3M68%31aUOU?6n;yC$iAVRiJ7ByMQ?x9mrKOA9RpaNXoo?J+g=%N< zhPzx(gOjH%+oNOi{5ANzWBH5+Y<6=e-JJwQd<|pu_c|WOj_#=Z+LN!t#rr31R#w5e z;`^rTj#lT3JIuJ~tr5A_$w}lJ88>})JHFSsYxZ^Rwj5Hn*I!o$eYRKo^IDQGnmDxj z-c!nB=GRKMY@2kYdvj=tCDZ+41keM(19Q?CFfr7urB@&Eq+4N23$hMdobE!uCx@>& z3(mQ@bA^A=+}25kZDqA=C5G*%D{P@^*}BXVw2AW~XjOcb_CHFWH*ANluvJ#emUO?M z4Z1&qCKq%6gZ8*#d*cdQX|-sc`GVGMegv(kTDG}{?S(6B;cD5wH*8H8M9@}N%Qkj_ zC|z}hEmSSrCx$I*VJpl+6;(HG{T2$^yen*#)w1m}Y~NpDtEiSOb&;Umv8YvJGxg5Y zYUXOa;i|a8l~$c){>6fowK#%hSI6~$;o5$MOHN?dy5yO~sqDfjL16J6saF?Syd=h6 z33a8Rk?yWw!-)S!7Sz$82q%VGrEsS_EbKAM>El0JN5!R~CSLVQ@sWa`W7P}ApF9>F zV-*}N{&LOX*cyNNTt(SR*PO}siedMyzdew&`~sf~eT|h0>SgkrLOPD`Ojfz$*FV|7 z(6q|sCHCkA%Z}+qq*uDNpGonB&s%LhG{o!Zup4-$;iN5cu4Gw*DgnmdT`PZgrtl3k zY4RnLe!-kTz3oZ$m%CIo^FFV`j6S{g0;49!$?5A+F-a>vT*eJaRFH&Pn&& z`!@89FO9&Ly02}xu2WHjwaBpUGOP?`limY;;fTJl<@z>e`&LFkR$A_D8(aE95tNYS zF5j3GU!`DQmAh?YPJE?8mnz*~H(nQCpXa&^Kc2&+vx#P2f15tm(XM?Cw{7~|Ml z&6F+2_*xbX^E&#ycz+x5KzS$Uvz4aastFhARzuBh$osTq^EGM1JSMcUsEyUIRt(v( zZ9SyJ?vm%~-yJsY8$W_q)dkCrx8oLd_fUf6uo(`$7NZ|7N*4MvJ2Mr z7WJi;`8Te)6qOQh$Jy~ClDd23GHC4u%U12FDX*l(dae8GbIEnE+&zQ%EmuyW(vMtl zJ3U{g(Vh#E+wd)WsXW?IwG{dE7Wek&I|P3_q-?$^GSbN&hHaQ^`Sc@^75>6`OZv+% z7gT#ny3*GswS1H!L14KtrwIpyW#+jdKZnm-G8p_;v*^5KN9%)hDV|7gId5^apkBrC zTRw|Y``yZy>Nf~~FN^qu(na6#jY<=F#ks{z+}0WySI=#e)qZ#5ww!3@3VrAPuaR$_r;MuF4v>Jnxs$2Q!NkqlcmMfeRVm!8-6a#+YX8O zMwAPibQ#&iIizVavigL(xVUYjmFFy7z&RUfPHQWd@FTBYx3swKxRsH7ky2DnqQ_Qk zEN=?&#B)AuE4>C`jxX7-s>b@bMc&x@IH$(;>Azl-7=4zbFP(MYD6SK%I%{z#Q2LDY zGTn+zP(FT{!b+`((yFr&r4cr-j~|T|-@A=fR8S*5Ugl}3^rgrP?=xq4fmxi(;^FtM z>d?8Mn3rx*3({e0YKo^NKl!Jocw3TQhi-6x49M>zW;y!2SezoS^3R`@^%(-(M;ykChDe0raA7DbBM+s#x*20r!SQSw|V&t7>xD9;{wu8?O- zp3CJ~<(V_@1@rj|{e7&TUu#@>v8`}m`DkZqUG$N-kKe~~A6Hy-YwfDvQc^f`B=PCf ze}a&^D|PVI2&V;M&cM4w%aoHoEbTDHtXDOfF5nX++UfTV~ zUhRl>Kipfd-HzyVt0*!sa?bMU$Nr>at@r%Vs>h^bTduY0F>ksRjzG$p%%^|&ld;~g zCpGcvvHHO+-B;hO+7lUSIji~fsXq}<+WSX~PRTeGU2D-PPr4O~SS05Pkd9_s_vBthXBEBVvJFi82%ad;12}C(9`gGNwATHha z$5E?tH zuO6d^#1YD_?a@QtbSn)8@mbWT-9G`Wy2c<^0L$Hur4fTnR{Zbk`{Pb7{i8wumJaQ| z)*wzX{4mI5&P)Eppvuxej?fY@sKRajM*X0SkU6b}`KYT8OMtfc2G7!|=@$712(9uW z=bGG5dC}rVems8B(gA)r0V#h!dHf^ual>42$hMkITs+ zV%|>+w?&#RnWkBhrj~`jbxtPO4?r$KNVnjmAXOxH11rL~*1aJfVE5F6qZlC||t> zOq74(>Iy?$qPnE_GEaTd?-nlYq*CKrE+kr*PjsnpPbbw{s$27kW)z-`R1ZtFNoTYs z%qFTR92lwgna#`#JF9jgJ40HFI;+k#w|uXB>+A8`O4dH3@TblyNgXdt?4lY7Yn4d0 z@1oiTD`pefbBN{;(fNf$UHO5C8qOgaGRM$vm_wu@wA?wwG9%^?WluBhlOZ#ZWwNIU z&O*otEtfe-7&15ZwitSQaLtlPq(Wk!doQI~4>m_bw4?GnZ&Gg!(|po=Y@jvJqm1JQ707oh&kA z<`RvA%nZnkV3~17rT{WR%N-{&E9Vl;VwvDVqRkLm#zM1<&`t;mEq9g(mCYr}hoXa! z*~2pVM&=}BgqE8xGUw+KO@U0pJTnSaEHlN(1nqgIM?%b<=!ho z<@1P`m7Vo4WJ+0Po}pDiMrgV7MCQ^wqWdA^=LaG>!!q{=jZn+`%_s;l_kIydyPt^N zmK9|~sLlOEL*VtdLPlu0(?n*%{Y29tGY>LjSZ2DxSpgZLQ6*B5Ya#);*dUh0f*dYd#H9Q zt?;8BDoK?U{?G%Fw?Y~dd#ZLST-dXxYOS&h$MsY#BrFeENE9x7tf%Uz!i9Sy)U87O z4^t}&8}(92O=-5#e&nFI6Wv0Zr^j+#%ki z?^#4NJiq6}d3Q~mkw0a+L~H(A30{r{Q_;V5i-;Iwcz&lYd{ zo_nTq9G13&i^!s)!g{?`i{OyOMAwsv8XN@puTRjdIbK6EKuZJPOd{c99eoxPvHbA- zPMs%Azjxe}X=5keci;5;ScKchEWTo6r+cPPnsV3g%@i_twTZb|F$=6F)6S zPMw4qCUV;i!7Ju>xo`Hg{3-WFTB(_g$_xPVUKjyf$bf~r`lzHvo6*dhM5MV$nt$Lf z)D4*s$}t10g;GPZN@yVwEyBoO3KA_Q6C~J6ydm+D{QGB296M#&-8@NRt{sY)+kU)Xig^aaTA)=l{e9=n1*_B}2IzaOut7uO|8AOyRJUaY<<$Gdg zWUBgeYC=RWj5g(OgNbSo(VXi{eR5}0zC1EWw5L~X+7&Q_Uu{#??rYZFJ9UT}5z%L( z41K*rROBTp8ED$q3?_Q&$wrw?TNA|)(JXEF?qDGzryz-ou=6TM8M5{8=3ItKYIKk? zuq{}_0L>LA3k61s<)Oe52?U|Q12u^(B06w0QG*>H^{6|L$V)_%1`&1XQXFV}J<cDFlK(AV*nm#ZAz=3DMLJN z6e{tzHUOO+Q-5ZJslPpnM_`F_V-2Fa@4nl)5BwhRr-0ubLByHt4)FIe{6S{|1kScH zfVCm86arfy&=Cqw$`sAeKeZ)lJLd6>elh|BGd^!?rlJ9+>R2bE@NV0bnF9>|N5iB8 zfz>y186+AC!Z#fKiRh!D{BJ1m#;vCQJb*F*R0lw>KyH!%5p_a+H*j77&Q##s3!M7E zIl*$AIIn_W9{|-teIFaub0w6ZHk~fx;f5zclbx zcjE&mp`aH8%An{8&{IKw1at@VW}puN{kxH7%I34{ItgF3;W4}kLyaH3#Pa03)|fkmsqxDi|9lzW!+Mj`jy&&=MFF2ZP4LpzC1J zQ({n%=osd_2tdyR=w&Dx2StrwP(Ju3fzJcJV^G)w?XA&15(bS!`|Z4S5z#HJi303@ zPYf}H)5A^qO`a^rz1K}9IyQezhIgV_p8oM1VxP+#FpkS_GPhu}c_h`yl{0W?clH5J z^C%RkFGq|};AhSrDHKrHTY6(}nbX+BA4*Cy054&C+=p_I*~RG7Tg)aj689wIQ3gyr)N(YiH!c>%dBbm z`ua@yak44@i}nG)*#Mk}fzuB-BWh#)=K^R5fQ|v^0Dw9I=wSfe0ibpO>IuFy;B*7d zo4|Pw?J2;yA2``T05tA3y^DG#)^&1E>~& z-h@H_08SZjb_1srIK6@M3XXPBO9X+n}t4@*UPWQki;-5p09g>7rJq{z@HIxG$@h zNvoYYJq-OPSsT?}P&UqOr$N5S21foa! z8omX6vH#x#!tE#rqYR)-Lz#^7yv!ZZ#&n~&l^7Csa-le0>Y>04zS!e89(;?y_W>dw zc8;NgPxh7dA1W!e4bXa|V7CFNZ#@>L1$qN#GLGTLWlF-%9a)SU3Umn8mxq!P49$&jrkDM^ZSKz;Bo{@Yk}mM>(c+|4 zdPj=M3BTYw5-Qj4N$EJVdmFhT@c|0t4<>r<>FnNp2g`jy=3$IP7~6huFyD8Q})#ySKT?7&e$_ zdhG{$Jv4~u@i%ApSw4`bsFl+NL-^DHGX<~0pw2MlC=7WYhFrpB)pz0}6u4`!xl8J% ziGqARw@|Lh!n#IV<5ZvHg5X;WVJ#R^h@rM*Dh6hBL(CtUYYZ;WHdAtsaXxB@6Hv-v z9$#A@Yf9wg4y5`S#_+R#>3>*13*eh@Ul$|Gjskl($-5_n4X-vjwqUln#!5ZcJ7nS zh5|FCePHIshO8j$9FY!$0%PTEaVT&BtK*=IVA$C$hfl{@0H2r&{;z}Z+EzH7jzdpt zpr@BGhkIp6LxGs#GDR7Mqs&wtl@SXCnn_%kp(jefsdRRm{oc{&aS9Z_Cbw*%%>B|H z$_y^OO@=72Mw~G0q?&+|bw(}}2WGUxwOlH8w>J@T*PF=Z{0ly_si}D*^)=c*L&Tev zLv&9J(Mzdj_e;w%-hWdYsRt<;g!Jppt#}4*Dp#5-a=l2FW!JtZQp8aGqF5ew?rvqK zXpY2>?OC&-uo>zkW!EeV0qj^8mbdjOi8GbXPDyBjGxXC4FnPFY?bF)C_J3e1?uu-$ z;sc>TIkMr4k`0IT9N8spJp!v?L3c5fZW3Q0dZ(+Y2T#Ougc>N&Ab#HDuFzFUn94eVCz7cj-Bf)vZjAURy zL(xA&@0JK?JLTr;HM5QMC=|Fj%w#H-++aA)BttLh2&envdb9lY%cmo%bRE$9Nxf^< zS@EqGV`Z)Qf9Oe@4q3-k#)TyYa4)q zX1SF7C__r*fs^{hxrk1QAwny|CX zc&oEZB9`Oylawk{@^F8%YznbCHR&il%(z9i=^47a^ehxuAtMuZ3XEds?jdQj) zae^{XZbv4y2rnp3o6s95Fqu@~Z5jHo(@Ul#Sif)W9HI*~ZwySn*=)BL1w&7+KBq5Zqt81pJA?ChxFwwA`>oao@Njqcr>&10m|1Ch+ z0;f8KUF%yuW*2zqTWq6w0h4&NM3TD73^~0jvE6arfp6S4i0I-EQ+pp9W~N}T_>iq% zHR-vtSnhtS^t}T_f0b^E2za|R*ja1j+&)9!h)A|}va` zQ$xy7V4hia`Zu#2os*_r_ebEGW^e*GNg2uv$hJ;&0{07^8j=^1H#T_1Mueg1tw>DT_KA`A22<3O7=7}^}qHpe9aJeCbctJaciveiAcG=&o!@TTQw*8ya&tX*t0f2QVX9LJGPDr`HsRe^_fb$t}yukSa z@~cM@DPI2v+M6D>$1)s+6lyw_NpVx6C?Z;qEO#jj644KmRuip2V5y4>3;r$v(Mr7) z-u@zT$$hd+%d>i*JeX$U4~@cwVybw1d6q^G=F~Kb_G7(|9Kw4=&CKcO$)yhFhT~DJ z8W(y0t+G7lXFrUQ8FjNcgs#DMd{jdFz|6-TiGQKM5m|0y`qphP+hgWOa>-QT)RU9Y zlbN{ym;fbstCGEKQ&=#G<#&1wn^D#K=#4}p3we`qn)I_$OwQL0r`bHo*=(m5LTN7vG>)z-cR-<%J?3CShh%QIX9Xlw zZ+}zaTrmcx>m#_5y@TJX^Zqkrl$qnroy{H36ELJ31Q$n+OsCV(7~Kr}G$*EsQs zK%Tj7bAkdyx=hkdY zJk;;IfUnOEY|5B5+>JHn{-ZK{U_pRcApqPPI;OckwS5* zS%DqqN;Xg_Q)0g{Zj8kEOh?N7nPbh+>l$O^yd=zL*Zm;rgT1&bzd4-j%4*WlNmYRfc_Nd(_|!UT^qMy%bS`Jx#Koj|6wNu z430@YvpPvKIxsLxLS?9=j(C5lq~mqQNA88w&Xl3Q*!NKxsf&FFH8qFKZ?er?|A5H) zcUhKUX9xC%Ni((42OBNr-98>orbq7%mjgth)#e9HPczqN8=%|GI@fOsqpdp$P$DfnXcdO7sY4`vU;&BiHyGZEUI zt-#n6jDIzZ**AjkbMXBaFCr7bR{*{q;M)$qufg|=7 zgRwpUXMpc5@Ero*Q1C^8Z!q}&0lsqZIp8}ZBNqy!GG8#XJNtPs?f_#)Fn$e2{z*U{ znYG}14t&kP_c8cR@PQ<>JNu&W+1h-6;bQh<;L|Yhec*lXll5>I)OD|(Ux#+SiZ3cw!VI|;rP z;0uHAW$?8I-|#W(Vi~5Od>hLx52cH@T6GbspNbqRk+LXINY|XM^q6*G`fqtNeR*dFua5dM%x6Gk{+Fj-r3nX^OhtoU(FbfPrGc*B3e+l zL*_d0*93ny+9xCM3_$q+$}@Ny_9OVV2|XApX<^Rw^h1_OJVrvGC(0d2x&8sczX+Y^ zd%Ow#%5=cF1BuIvn2NzU=2NQkC8SqrFHS%=VUxR=H#gq@MBJf@} zbEVo8o5ux&)^}ys3k3>g7YjS5hMCRjI64xKQ*&==50xAd`B30-eCF$7Z?lU&ex0m; zq9!J>pbg0Pi*OVA1e~b?&h`m%xiEIY9BjjH@thA?l>MZ6!=cM?K6o41@oOkIqYU8A z=mg*Y@!#KMSrOeOS1LrSP~L}f1j+|cW;rHVeG#8xy-5rz&suEKc710Hlgd3J2Cc|? z9tQQrN3dRZ%uUMDAx1xKk_ct%VR(1z&oV=ri7Yk&N3*-oJ`3*)|Bd!{M9~c0pFh(@ zMB`*c%d;+F1WU!RP|3Dh;$wYU<4x*IL7dA!Gso^e&!YY}obx9jbWUq*1YgM`>Qa2B z@A5ozFYrX3xd&)$uIn;qWtiOWc8Lq2z;^i@@cxXwxX4)EMA|d@!l#0dFE`YI8UZ z(mb3}Zx0Z0EScWG03YaTPQC50I!fS#qj1=KD9udKOuQve=x6G)#p{X2n2Ko~Ik`Ma^=pS&(#{Ty!atEKnMoB3j;dAfHM+6%5_5+&>sf0h5>7!=$}xu35xun z2S9HQ`ijX||GQzp(=gzA81Oe35CsFuVZb>6wt@lCFklww8=>d{C_07gxEbibLC@65 zSpQGKfca=>CxL>f1$?2t_`(xei^Y(zqh%`WtPn=xWf<}}40!>&Xd{$+v3sI(&5!N0eCTh?*Q=s zVNNe%?!LgB_6L0q=(m9WPt5gyF{K}4O1Gk8N8wZb#Q?tlg#jI4!0j*~0|xvZiVi{1 zE+}dR`puws1AQY5_y`8P0t0S=0mU#Ni49=?`wCv22m|`SfF>|tITY=LqP0*I1$tM| z>w>-n1{A@7l`w!{z)~1+sw>w2t1#ds0Fz+AF94hjdLb0e1^qY_)dBr96x|8><1k=4 z=&|sH3owNE{-3BkYqD_$YKN)F#z@S9A;U2er7+|a6n+Rp`hY$a^jy$)!jNxa$U87( z6AbvYfvo@XtUfT{GDe~W3>XFjI>Ufxpy&fA+6F~Qpbr53de94Dz}qn3IT$bq25bpp zF8nay6BuB@fKD)=77SPnMK3|oV^DMvirRu62l^b)pM?Pr!GLqvRf7v*z;RjUM9;&3 zV^HLW0aXCJ9rP7YbPwo38E>xL=1U+6JFz!& z4%ed3Xvu)c=`Yu2wqA^K39ek9lH09NpeyK~Nv0DDbddu`DDbhQV4;$C&HKa5uUZie z9=C@!)gqG5pFCNMD3(7=W|GT52)A6{ONwM?y)OBDxh@}J3_LCwjGa|SK9~>+e2K*5 z7UXowAvzpIRA8G=KGeib>J*%u{)3a!an73A|1=t!AY&;5!%rhjE*Hi%+;P+&LHz*g zvr!)iLpqzwY3D6T+CvhY10h$r* zOd;Bc+^$cWNyA@5KED|s$xKZ%msy?UKoibtYH)OgB&D|g$YjHTs4NP~x7LQ3Q>=4J z8f={)bLlwswaMvL$r+F6-?+p55%mi6e4m^JLxIu+N#QbX62(MoWV0dag_F@;=6pbv zQih%1+RFM51*V9zlsZLny%sKAjdFe?qJRFpC9?^R**+=5`fiNObU77=0*_$?-ZURd z$sA=)yUuS$Vc-|Zrf2B0xDDGbWvJx0pj?TDN(#`U^AZO_fqA&+dquo^dlr9h^F@4} zejmO;xonsDiuK3$no;8V%3Z`ixxl{{?OSE>uL1B6FkJl~|KPX4Kv?TH9cXl2>&NBL_b9l^^GR#7)`V?D+Vfs{RH+<2nC1NBVYk)mPQs)z#H~XX2iU zsCO!&HpiPrxX@?*$297=pL@rLmY+6TnxtreDmi8He=SW)i&D4ENH@t0nYL-G3L$2D zTb%2zL#Wl3Az5XEe`M8utlT@}HV1$|7H~w%<*T&NSAzH%5=Gw_~xV zrAgN$8WvgJ+*IPen6@f$KaFl4wQ;dWZFK*LUSkxwPs9vteDL3%+%&e;^7QlCmT4L3 zCRs+Jp*An}sLgIv?4!xM1<;D>=e5=D#U5?emc<^m#eFq4xmSra_fL#gMTXB!iHI|6k^5?FJ-1<8Cs;K+ZvPebu)4q7(?9-xqsaXvzHaKi#h%<$(+sJN zT7y>^7AeoHyfm7@bGFfq^W~*+|5Cj&p&{-P+Y+q|%g9SJg>AF@v~O3`p2Z%u$Gtt_ zys_84C9#FE$X$}y+<460m}nb|++Pw?jlFL5YTb>;-2TxoifPi|APJidL=MznabX{$g9n8wp?l-k+8~N_3T0;}^?=y2-n%>lC zZXK4?xk-ia^GF%&`={X)>?NthovA!s_oSu-GwT#W6f^jNuLXv}8|=;q_It*keWU zvi12Q4&uvBG%VjFW#*}a?wbuNjLq(blmW&;_qUW+jDzmFh9iw4_e{eF6N|J%MGf-u z`g*w0*bGMFK8vSwG_Xj;=B83YoX?8pMZ;Y)ukqUaY?)T{lr&-Az1X96yX_kH4lQ2B zJYHKZmj{j}`O7@PP+_=05JGSiOy9?hRJE1c0!`2i-@kvBq-uq}3&gl^=84q-J(MxYPr9%bS}f!LwYn zS;XT|zSLte(f6kckEjTzwhZZ5mPU#=a1Ls~3ws9-91AE)B~`K1V|lsT$Cqld;0yEJKOsu?JX&Dqrl$6>qRe8M$e3q^$ml27LT$JpqOZIkSN({#8cG18Dt0ueHbV`*NR%)i>~Ue|0( zDqNS?b4Z+*{^q=Gyk4K$;NH}H*bwX)-oNh|dJtl?Cs-aH=)2QRFZ;RPE40vGc8c@O zZ@?}ws>K%LpzCj0KT7XV?OVRA_X6pfUSNhYtQcAHI><-*>T^?D4b}aXZ86ec<~Q@w zqOc=8(yFwnP3E=R2xOV7hb_w9Dw;(1)ySyfS?(f(f3D03Hd>{e~VVvp*`)KGPw zDsxLZwnT!HY}#hXB7d_q!(!0OX^+>o*x@-j>B<|^<%%zj`Xy4bMLx^upGc;y@^z{d z-!GAngrpHN9FSzS=wKJ$i#TRAaVK_4xS`K=Zfw_3O6hs*G2zHVQRHDq;j>+P8^JYaB)KzHh&8P~V{&XW zW+ak&M4m0`pGcO$L1nrs{KBvdRYAG_B(>&@DUrnIe%-Bo+!(Z#yEW7M#0^EQ%pH~9 zC*DTQp5m@e?-kz>)sDIDcj>+2EL1JGS@+&?e$@Q#0T_eMrk`7uM4 zxOIB2HTJo$_q^69d9+tkxc>A$wcX5KON}D;yei|Ezy6lG zNhH((>!aTPpQ&5ypQ)RO>(uR|-u2x>8L@8PJ}oa>hxAQsl2ucMO-b&YjG0D}`)fvB z9g!r3bE{`^L~5Ryr&p(WWi;Xq+>@6UgVnh$v&^i#;4TjwHZ~Mav16i);=+5f|1gZQ z!WsP!8|EMT3x{1Z(qn8Wd|}`wGqmiuq3-kh6IJDLLzO2eLym&-j#~oRGRi zevjJytD&B}l92zap;j}2)Fs33QD=WO)UG&XD#ux@PTj#sfk z29r-H$cXYGf4n;Ko1vC40|i6=c(vuEp)SQKuRl&5KWV5RtE*UloC+O0X{x=6{+ep# zH-_@6!bE?xI{1yDO!Xx{ZYXE!F@CJ9H2pPHWjS|w|1QICs5Rg6^ApAVy!%^28S13a zkAKVZ&unM<%I^&2QE$ofj_(-kM|nQ-ouQ)Cze78iY5DiuP%J=2-*dwudDaS!3y)Ut zp*(8^n|A)GV7WYN1w~?nR`94iAN<}>vFbPBS$xD$aq44v-gu;)p`z7B0o`}RP%+9a zG5m(F5vf>zCyV@J(nziO10iICyKq?B^s~R4$~kGO{F6MhhrZ^%mVeD7q5plkn)>c* zLwWo@#jJ)3pET7Ww|rRRdR$-X7gsy_wV|RpSw3#4AKkjw>BfsyH4aAOiW*f&E(1XSe4`{G={5^Y(HE}epFTCL^Q6|tLEyigwgmwTou-SIXrb355j+|fc@G~ zF_z&c<@MK2BlVs{6Mi=E%z`Ikt3b^ep^g2zs>a1=Jd-GEmW_?INS=RmccSs5>Q%s= zMx#>|Y=@Cr=k}UaNKQgyMYSp#*P+p=O6ON-JXRHKt?RYUy;U_1L}PJP)-FNg;i?SU zg~q3=GUyB%3#)4EI7%DzgRhEyP9BvS;wjr(h0e=!y|bE%Q=3nk>esIg6|a1J;o&#c zhInPFeJ4$|<)EPwR3gX^#q;*g%js)FRa4bLe&RnIV=7LXih=#A2Iyag;*>{SJZY*& z4;iYass;My|L~e!R%wbiB&phLx!rO>VmwgnljY-lcsv|kfG|S`XI04 z&0-cxe7;cz=ZdOwk=tn2 zkaQ1`FN)Oq8ooMw9J-umm0i-&k{e%$`%B{vx5Z6eTAxVpHNHybZ@C!@U##it>P}kG zrRQHTBFxNl$;babn&7K6aG}8$5_}Hz@O4GSO+Ac!x7E$#<10^_d{XnNV{XCCO{2 zK0YWjS=pmw14h34>Db%qN0eD!E860F9vaYqNB1lD+S~1z@UoburV6`{+& z4YTre;oXzBM;pfq+fP65troe|$xh_^7&m=p8@|;UH?vurwO<;R*Po<9KFh28xlPFz zO&nT%|1k`Yo?kQFv@B9(?nq~{DbxK@1keM(1G73ZV4~BgsaGBHq?=(=39<^CoEt;G zCz~%hD^I&QvxR@b>=q3)TYi;n#hUH6%WO`SY+dFE+Jrd~vq%oZ(U|9sS?dIPtdx}i=b_;l5MtT`@hR<;VRjF)@%*$jiBXM z$#&blqV$o=Y)+MIpJ}$J`OPs4`XKYy$?7*>(B@obE0^=mU)i>5wx2Jvl~u{sc7dSX zx}bToo_c#q6?3&#bCq4@>R8o``WFgTaA5??s*3AA%~f=n%U=~&<-)e?!f7F3@eQe0 zZ8mvH+;%zCl{ll^t)Y4m|Bo!FZ$cuR=rm8`PI*|^qnFdC|Fn(@OPmz1v90jX;#0B4 z(}ka{h>kHY9xnWP<-yo$i$6D_EJIbF!MBR}?z>Oj*Wlb)K8gC04I`w^%5xg2IKDAi z>fXL~bzMzUMh-8r3ujF$rWcWN+?r3P`SQ=2tvoc;YpZ-W@N~V2t3;k^#*DkYHZ%IvvU7}@8Yic(3&N-jK3v8PO*BkfIqt5f z>ovImJYRz8v*Lnu9ox6+oXP*S@=#iw%6HE_-N5IZF|Ak*k;-u!hwFuK4v*63@F%V~ zheyujtcv)0qry~MzvTP;3JwoG9MrS9nNQ_%rB`OEy`M8rnS_wYVV!$^6<$Oj%`7(+ zU(1s!*Ql${=z;OEF+4b2c)xNe`#5s1yY@&5oJS14*DObbU$ z)3I`+zDICB3ipi9kD%wfHP$tYcOrO>Yp+Z3RT$_~h2c(Im*p!rFb?I0`^LJa9m@># zK)+Z}A6%t=57hI^1sRzVH~yLI_{|ZJ&F+oQG>Z>MFv9M#XHw$xBh2~krf0I_od~nz z{_#w+`03DBL2kQe8^n(Ra5=fdpUsLN3hT8lPhC}Y(LuX zf^?nNR-eWDTZ%Wz+c}?QDC%vbaFK4-Q|ywwXPXvZnAXc>LQ9icn)PbLkQLj?Ln_~0 z^n9H=^0h0+kKh${&a~pKxCPxklwkU}D%k93`R7djua$?axS+Xgep;L=I%l>vsV_Cn zyJqFZsI+)1&Waz=pu0ydxR;$XEu$SZzGo1>@5)Xz)cLb+rx$9~ z-*`^)9KLVgERR-H4TF4Ym3zwz?L(Dc8W!IgY3WoC!`4eRed>HA8oYl|u_&NWqDTBf9H^XO5D_VU)7vqW4s2GdGWV!TsR1L6g?VjlVCB)IP~febq^QAx||tN{slRmu4qDNb?AVwxg(_+*@+&@XlZ)W zh$o(NW6MyB5h3`x{fcU=k6Yy3t&j6-WCH%yqD1R6ZFT&#`&MDCQ2A+-1GS-!NH5dP z*aXAJuT@y78BtoU6Y?wAygruDT6`ZQ8&M&JRC$@FsiBUejhTYP@3$%=4}W%5Rh$lq zdFduKAr&^KqJVzrN52$r~nY8>Cj9F_pnwE6t2`W`j7%-~36c$o=Nc`fmJ|rlH*t@EwtdiiqCh z5ej!_jdsd2OiPC?VI9Fp#pI?*XUosAdq>NAsxRa@N}kK)*(=Yb^6Zi4l5^=SU`l0+ zG{|cKb?lt}u7&zJ*3YjvF2Ce9(8*7>v`s=Mi97joEO+waIk(2vI!z^^(+3ovI{6O> zIa}Kfz7pZ2AUNku4oFGbYb=jC8Jli8`e@|QhZ&z*>aE(ScmD#p)XPRK{ww5CZ@O7w z$Z5-?4?aHiwWn&xz_!biDgFFfCUcp)a9dq;Q;tMFb^kxuv~^qCHdl7@ez9r!Uv0YI zn{JjFYOU+vUOSR1N5;C#_NzzglGu>{SBOg<`PzdXd^uYA)SJ;&ckAWtZCMNZsC4Vi zX!p|A+HKy9PB%A4Mn;ZZKDFW>I@V&x)mE*Lj;;EuRV%#dW;g;VM>L=Me&bEWD9H|n4 zT>n?d5)Z%J(qk`YLZ5o~9}uhUx_a#2^|)hq)NcK*C*2$a1UWAHRK-6aEZudrO%-C( z#=qKB;Yl}#0#QzuK6SBb#7B#-9{7s_xY-R9*J+~r#79n_TJjIRFsJzHE-mr8AMdQ) zYKb@9><9z+H0o3CKLAwx#Q;~FX^Y#TBw_%cQ+?`a)%LrSO4=q~IZH>~l3jILaUS7^ zem=qa)S`dTUtV(c04x&yC2r%l>V#wf^zk&zXIr)ByxwG0>3LJNO*hGZtw^>V z6E|`evG2U80{rj=r2PHl@oMIMnz{0VsV?frJs0>*m^a<*K&teD$vZitY`kEq*8EU* z!Bjis8*7}%_V}87Ms{ zkKaqQrr@J?M*V`P+ZnB+xPFA|{iFG@rOMCRCRqREiC2$^!0nXF|({yBPX zg_tv0gi_`Zm#! zLm`?5p;Zu?&qC9*&_)OeEoYhtZJ9&Ftn93NAhVfe=4e_uWQ3M8M`VuAA({&rc_5-A zEHgKxg_7p#Q4nIzToJP760zH|qOL4WMD^wp4TaYafQ-;`?i863bBXSP%p}MRWSP4( z&V0xSE$1#O3C$#0HkT+14z>nD4hv;X66KpAB(xmn)Jv&kF3}xOwhwY!Sndw3>=@*P zmUD*~SUHzyJY-_$kzRktS!lc#N|~oeLTEYTMX2RGq6rY{Gf$6%HIHcM1T8ZZGD6Fl zATp!p5lw{5bjXZgnTc9vv6cyGV$MVn%AZG+HB&RJhtM(>%9<%7u?32RmcyKSBuZHh zE9W5ON<{7+k*k25&~lhl%hA2viL$U1lJ3<#J1c^dMX=?)dNhQV!<_mvu;8H{MqP=+ zH{8o1cT*3ejbRmh)x&6zT6C|DyhE;tyh9OrON6^lPos^IUl8nRv@p6B(Hb&XJe?`d>sRFbEWZ@mKfHkeeAR}koBBpV|NZt7(;2!$7D%XzYS z?)b94u$#+TY=8pqjjtx`Lq2&uS#_+sO zU2Y#c{x%4;7Af9qHeP1v$?apOPQ8o6vb2>hAPN^W>TNU$*$atUla3)A68O_Lq*oxX zsOg|t;G01te5|7FLL!zQp4X}K_`9Z!oqXqQ6YjqIuDe-;+XpVZY-6XXcTJo;?$2hL zuJNuV=4Qn#F#k`$^vQS58as9J_}j+bJ#pr=33qY;md^$l!p; z{E_Bk(wy1HXwc1%uCWVq*H~*xNOyU7UZ+lXkG*r^1enQfJwiky3LffXGzg7>DDP6@h-e|{Si&5NZIkc3gJ)0r;CCX^(1Sf;+}L~agx>Npy;DbSV8O}b zN$qw_-%ewaL)4Cl+7nR+PVZjGFp@g)m<*Xll;;plpHFlve1>!0Z5?>5367UGKeTscvSv6L&coV0Wq+gGpEowbPS6VZn^YWhl>XtS5- z^?|zmfx$#itgfF~s|8UEuUDn{Mz9c(J+A>5VS9sQ!j`(GG1r}9FOMBLf%Tzk8fcnW z?gR#jc06&kNAN^ULv|>5K)&dg#mwSqP=?(0tZKOxhEr4 zfQeF*xIQq$NoO1))kBxX=;*G|T5o9k&BB=ZZMFuO(?XYLQJ=-*Mow{b3k}fH*7e6m z==zQuc?1^Ofoeo|+;N9J3H;}p>-Ku!zkdV~=ff|9zq95K**8JpI0RxLumA#UAoPfj4i^^``*T6+m$SdI55`2oO;V)L#Y83&0r*oN>TO0M22S<7|5=1UmyL z2K9dfXeoev0BQxGBaL;>3L!TUaxtj?0J)oiGZFO}@PQRQM1M(Odw1;v-$6k~2yBC* z<)Ej5?tq>SdJ^dUKrbJqM=l!l1km?`|0UFwMImvDx){CMr>H!(%&5*LUHLSS40#(7ZO9gH`leGu9|f+25WE?+{AXThL{VbDex z)B*pc8Cc>bRFla3dx`Yva zUE_r4WdM~y(QGJ6fkAVja2oiUg6|9zW}v+t+ULNa*=WB6XS@LhHGo0+Vo-?a04#bQ zKu-baIVc(hgQ~-zT=3ljzH?A`01Dfqy&>8Mp?wtEhx67&L<3t81=#rH47ZdPtU*$riDl(kS^gxpb- zAEA5`WfIaQebGY?$fb}|e0x)-m)RY9%1C5nfUm1u3la77X}Qu= zT^>Wb4V(ht%m+>%;9Of1>t6w=AAk-3XfJ@80cbveMgS-kKpnu>95`)&vjsRMXs-vH zyMWUx1fV1UrGc?NfEoel{{U2ob{~Ll2apAv7~s?fUjlGy0OtwdJdgI!|G+R3K+ym? z-$M^|EEq4zHcjLO(1QS4jrQMwGXOZ}n&>I}1vnRK=&AV~IA`Le9-{dGS`MHi0O}2( z;{YlL(60bG3ZS1f5KRM42sj6T(;hhA0OvE{d@DF1qAvh+2tc<2=xzZ02SBL+`V>I# z0cal#`Vcr}z!?IZ3BcJ2oFw49%Qzt_v$q21eE{tO&^rLK0dxa^HUlUIKwDtYM&N7% z&a1$A12~<4^8%9GXBuGrza{~L=!hIa6Z-C!fHAu7VF?sOs}WE>mv$%c1_DYM0?B@h zqkJi{{#SxvA`ngBte%KI=TiV5jS=Cxwbb=T5_P$o5A;NI zl8+%oG!k+}kQ)WLW{_J1xz{0gqyyG}HUuAqV1EeKhTsecJ`chDP}mJ}(;?R#a#4^Q z3%LTwy$88wkQ*F=U<(MILYh4cg3BQICIo9kur1{3LhdN!6y)YYZUf|^Ajdyq<4+9a zLi-`u34*y0Tn)if*td`Ip^S*mw9)0ekV}Q!&5&CK=enz@K46?5&HP2d@waHXM@H(h zzitoF&tMn{hQ(lL2Y`cU?}zr;Xs?C#y=d=__FS~T2SaY;I}ASZ_aK`8r9q3U5&5ns z+AHUb5YZ)@=nJoh<lb!tU2@nC`(lqlkC~y&%hss4+%hs5q+=_)ZR!PVr3`kwdnY zd-rBOqIC(37hiBPyJqXtZ0%NhH?7V%?0@$lsZ6_G3pT>(^q%Ir{(`(9*%j=lGZ{Os zho=7^>)BEvIaCsTm!b{*EQR|Uw%Y*r(nOuymW|itPh)l2bSzPb&t#=zG+`>r_nPYU zycLPbk=nZ5ML?-Y(f1G|8tS2)&|Mp}s+F#vkv)WHfgC!+_OCKhw*3R>PG8M8qc8UV z+d&wPG7Dull+97rMft1D9nq?EtvE#t3EK)&M^bkJcjRbA)%X^H?*l|WY#%@eAMPvb z-zk2>(m*Sbf(->w&)O`uEBFwG*la{}%tN$fxE`TudISQ)M`-z6$q_5m30VzJpc8Oz z#WDOVnUb(QBFMN-plPU%JQTl6 zRV7l|_LSaQ?s@S63giwZdj83*-aQA)eL?1@7>UP`KZLRdGJtJw8zkrVz+M5~lhFvv zrj8gGR!c>oG`LI3uwC9q_jnV4t`nTF{lOr{8)N6mCR7^SEb*ZlbB?ZMzfdPXcE!46~8{Cu3K9 zUv^ER*W=jG5K%!lejrN55I=i+3K9Hh_E_sOF=%ep?az(+xV0Qo?0q~~+ zOw>HmW9bkDj*FpT+Zx0d6{|D%@;gBGKU)}_z!V7})77iJ^-acr!9;h}{8z7g2N6B| z_RKz^fjmXc?N%7V{A=|TY=A*6VaR?M@(v979hX(*;v*Eeaj?EiYNLokd_8x!T$6>B zx0QCPJ-8q^gdvQ9AuFUuwtZHHdSFHy#QZ@y+TdMTdP;8B&PUa70;)Hd$JbH^8WPz# z11TXx8-Cm`{ST`r0i2Edx<8U+Mgo1iXy7~0vs&0}3}iIxyJ;X3b4-Yw<8j3Ly_4Wj zHtI7V_ii&He+!~bdi~q>EwXOIcDAfbOU-VgdvdfHQ8d4zmNT7YPm;}s0u!ZuVCJfN ztRQTECLM4BBkOYA37o*{_((=DY`-ddi*3(p}5La?9pqzAf!eW@y1pdZ-@| zCk)$ZI-mr9k_*Lw8L7CIOT+HA1tE8(j%@Z9@R`*O^=qsz(f%PK-sEhesWC*)w$-~| z^Pu+r?3PjwQC$$)wkG0W*9A9~|CY!{>K<8^UHcwR6GPQHu{>;#Zmy?js>F|?;1noK zLjAO4%Uy$KC4`67fi5g>siTt6l-rvmp$Sb_k08K|!BuPL7CN?X#8liE*O?$Vkl*cFA(kQs_WfQe;M^=T<7)w6bNf&**SrSu>4BJ;;>yO zRgcUNNhGGLyBlgBm?mCdp$5V0`$Dc=W8HyUu4lzg@vY(;VSAaBM2;TGfL%}YPgk!> z1hnj3`sy{ak@Uz3R9vSsm9reFc$H{+aWgnwS!=!g-j?NBq2fUABlWJq}Q=@NC8}x}Dm}oK~o@GC~z^eWtxX z_>?&7^x(Fev|I}K6M;Vn_zwYpLcNd-W#$iUq|B%<-ajCiF6(-Ea6N!#>g7^=M23{; z9OgJ$c1NP4VhGUzWK2t?$4)6-Qu>6sI_PkXyPPb;>=I`Y|PWX_$yTD`0@cc2Wt zGE!foZ$wX5!H^FnmJiH$BU^^PPgmImo#Ow>9GBZekgV30I#CjK$>TCIww={qkL3Msr8tmmkl1e9JK-Bc2N9kBWlHY@dauYV6d$tG2A!VUd2$(D zp~hV+`YTi|M8M(FUp_287xdx!oi(#M|ri{X_y$g_;e8 zFA7dr{SUe16R7`!`i6QGqI`pBQw~un5uFn6EwT6MS5a}r4zVQFFRGK zm!tiiZdVxyT;nxPAX`c&vzu(|M2B&|a4u1@;y(AshqQOMlWo$rZ$*!v6hYg55{k=^ zBhK%jeWX9O)d#u}Jx)Z+WOppLn@P{h?Q4d~Rc&BVXQD@lXtZChax=Yhf^srn5_u={ z`;hGOPT(ck=WW|xO$VZd@tpIW>a(C3(X|B`!EsR71oXQ)6TP)9RxN9wbGiFQYr|%@ z)p4O$LtXFNK-Wh?zJ9#MA1ABB350sL(~NWVfg|JBL@iKV3j`h;t-U!_?gPU1gOUL` zf$_5LEj99H8NuGe;FQmI*7A#F_jCd~(ZPP$O-~{@{Z=P7A$kelk9-q?pAFW_=^dT% z6u;I;*B|Vo*LxBI&n<0qR@@Nl{AQ$F-{$C7v?+~=KJP(vyb;mC9z@R|KHLkOXz`s8 z(GURD9HABD0O)fZ9(~yV4+G#)lv4n77J*9vCk6)f2F{1TIS;uql*>jD8NB}Yw$nXq zf@L@aDbxfklmBZ-6h%ZUk>xI6K_dEI(rTjn5Ln`IVR2fVHD5ggZ(oO8vPhO`X|O%Y zk2>o3Lql+(m?qv{8tjf9Os%dJy^ZxgXejR$)iWnxM1F6tZ#WiV)!dJ~f3Pgid0F%I z@}wan^&#{DY{&a0v=7W&VoUsU0-wop8{Id)ootVp@5}8}neCI4(CSPDfN21D9{{s; z!V-7~@)z4``PGpBqnCExrji-i_HTL{4?HKCRM(&>?_Y@M16(Y8EDS{d!u?&XfCebf z)a6Q{+jdvX`E4+08#b$47*r$%4d{D9mgB(8H`>TZ*+Kmt(Ed?}>dX^-|Hp^H_i&YR zH*Yd_O24zn`P$$#J4W_z%kGHFr;ZY6Y!xqeKu+;%`d~sI%iIN$2haqinAjyl||3Pqo(2IhLgkBUhq56OdLj~=dFx)^J>8#@(cywRsnvOIC=phZ2IB@=&Mm48A@) z@NCB9;rc5UH(=d9qL*P{tu{1}+(klj#=0!6Xqoh=YjB@MRGt;HqlQ~ikz4DHh_lAMm;w#gG$CG6JcMU!Uz!r$%ub@6hoXrW83b0+$ zA5PX>m-dIU?n?q8B&(G=|F;irRZj$vMw(Ef*T_>Nx7Ltq( z3`~|#=@iH5?6tUAGwmbe;ItEE=+F0EBqMdcZ{LRcka;jm&-M3+tYKM}Vf$t59goUX zS?bq*9Dk`K@U|$XKx(S^K<51&w1sOS@NTxQM+q05=;)`OSp0J?jh@Yk~1W&6pJc z-yZNC1D^@LdEjdgz8AswCHQ_51J7qo246$r3ps&hVEhjl%fWa97!v?^2l%#w?_==w z2j2x55hsuZzK!791-^9f{RF-=<_kI7vz`Lu%V2B<#xKDr--UCwXFUYIHQ-AEUn%$w z^MSd`ymhxd_{sq47=*T-T@LQj(e@mSQ;N4(s4#st0{1kvcf^RJNYJ*Q+VmaHh z-T~hi;2R1)FZgZ&UJ>}-uOsXKd{zLAC()DMV0;dYZve18_`U;QeegXFzURQ#5PYA2 z?+iv}Dfm``FQKcf|9M#@VB8NzM;M8ggV77XE#TV&zCt-z*n$7yWz#s+JqX2Y;Z4Cs00yvK|h%DYc2pVu*%y zkvAzJngNDqalu$e2bALWor&Jx(m8Wr11?|7xCY;Lc_v77Z&LfrN5LNj{$6Om6@kY_ zIS1uWcpG*EeCvfCa*FHgb3J_@)QQI+2y{UCGE%OM5L_&DqHpmEb)W8lJpzf#I!r}Y zw*HptbP4Gd>O5}Kv$4tL@aD$*|1jkB>B2ZYm?KxJ%L66d^p$EYY#t{NT8m}Za{?=5 z7Yo}*uhW~;SLld*wVlZBB<)V|XCm(emf%Zh6}|N?x}=$`f1;W?v7iFv`_JPhbUB>q zJviG3$mJf#F4!B}@OJi*p$oDe)^9k}Hk=Q3AUl2uqG-Cx;O}%1(I^?w(%|nH!8gP(r+9r0 z@v%M)@h0`z5YFWv>SK4GCsB8C&c6wvb9}NEd?A;pOJQZ-P_DigSe~oz0sQ*9E^~5* z&i#fUKmelsY^>#Ia;TT@Adqt3LIn zVs*R@Cme#q=Di*D6iviiaN@ObyhH&>2lsPU{{F^KOL_+s%h@5-yTa*j@V-6zvT7FbPGywG3ppOE5H>Ygu ze7YM53G4q; z81Nblm<0ohVL%HQ@RJ0PQdJEGWWa!iFyH|w+6qOhp(q;kZlKo&{k}<9|F6P;M__;j z16&wzLAGC_T`=Gm0H(lzivXMq`YI@z1Nu>9$4Q`9LeJPqSpWGjU^*I7B~TF6hc6_E zFFYR1laUD9-DN7Q;4F;9b1-BHM&fDgqSa9rV*7pv9V?fPJsupOohxkn05}bRYXCSO zfR6(x8s&=soCd%m0H(meZ)Bvb;CSGFg)&<})09MG*hwVZD-VDG8 z0GJEF#Q>}X&MK6(F_LG2YhYDP);<-Yw(#m~0OtXC1c2YdoK|4&$}p!Hpic#TAn02$ z*T*oWrI^xZV8DL(RE8M9^A7`>!hqp0pbHELL(#`j^a>QEfSv<-8_-w5fcIg*3ou|H z4ER47P=gI%{rlk69vILW2GoQBAt>4eMGryI1t@9_dOYZ}L4O_w{2KuR*_%00T4Ek8m73iB_$RQZA6NapY0spBh>%TPE83vrfNYsY` z17JW)81NVr?S`WDP*ekS8*~fw6)<223|IpL`oe&x8V>q>P;@)!A4Adq zpy)6Z<$yj9^qWBcUHd|auAiW@(e&H(wcB(FBw_o1BRGd^(r1`tKxAjgwV9>zP|n7c zYrfoWIf2%oe<+!b6KEv|4ku75DVS4StluAI?rTmoc-w>sv{Ytl(zJ=S$VD5!%47B!jVnaq`6kC-4aplYz+T&IE`KMiI@k^fw=(aFco) zPEOz8r1TYM&Fp{O(NGf^%Qi6lFhb{YkK-EdE7Tp-_o6-p^&kvssV}GP?UKqlc0;L` z1Rg?tH!`7f!}0x}N_}FnpVdJ2czyd7dJRr;f8;$tBcd&7M5~b7b;hq|UP3+N5x>27G=yNHVBajwH}@Qd&Z$~jy0@3Kp$=~3dkvz7So zH1OZ0_B~?qpAg``+HmE6{KpgcKjzMx#eZ#KE6Lv)U=`lB8I3_G*K7+b*9B93bp5y z=`(Ekf0OyDb>>4oAK+W=;vYAVy2!2kH_c9)z9{~3Y&@y5)21)Z+HDZ8 1347957792 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel. Note: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change. Triggers when the airspeed change within this window is negative while throttle increases and the vehicle pitches down. Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions. Relies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) and measured airspeed. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good. Set to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.55, "group": "Airspeed Validator", "longDesc": "The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.001, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for synthetic airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision. Set to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using an RC AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio", "name": "FW_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "This parameter scales the signal sent to the rate controller during system identification.", "max": 6.0, "min": 0.1, "name": "FW_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio", "name": "MC_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation, which in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low. This has to be lower than the critical threshold. This threshold commonly will trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low. This has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events the specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification. Setting this parameter to 782090 will disable the startup tune, while keeping all others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected checks in the commander, setting it to 0 keeps them enabled (recommended). We are generally recommending to not fly with the USB link connected and production vehicles should set this parameter to zero to prevent users from flying USB powered. However, for R&D purposes it has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_* parameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods: - one arm: request authorization and arm when authorization is received - two step arm: 1st arm command request an authorization and 2nd arm command arm the drone if authorized Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer. Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited. A negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the SD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition. 1: Arming/disarming triggers when holding the momentary button down for COM_RC_ARM_HYST like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Measures taken when a check defined by EKF2_GPS_CHECK is failing.", "name": "COM_ARM_WO_GPS", "shortDesc": "GPS preflight check", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Disabled", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed 1: Allow disarming in multicopter flight in modes where the thrust is directly controlled by thr throttle stick e.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which datalink loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature (see COM_RC_OVERRIDE). Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed).", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below the estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any auto mode other than RTL or Land. Taking over in any manual mode is still possible. Starting from 90% of the maximum flight time, a warning message will be sent every 1 minute with the remaining time until automatic RTL. Set to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss' flag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode.", "name": "COM_POSCTL_NAVL", "shortDesc": "Position mode navigation loss response", "type": "Int32", "values": [{"description": "Altitude mode", "value": 0}, {"description": "Land mode (descend)", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Set to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold. See COM_POS_LOW_EPH to set the failsafe threshold. The failsafe action is only executed if the vehicle is in auto mission or auto loiter mode, otherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold. Local position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT), and a high failsafe threshold (COM_POS_FS_EPH). Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed in which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which RC loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "RC loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Commander", "longDesc": "The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.", "max": 1500, "min": 100, "name": "COM_RC_ARM_HYST", "shortDesc": "RC input arm/disarm command duration", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input.", "max": 4, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "RC control input mode", "type": "Int32", "values": [{"description": "RC Transmitter only", "value": 0}, {"description": "Joystick only", "value": 1}, {"description": "RC and Joystick with fallback", "value": 2}, {"description": "RC or Joystick keep first", "value": 3}, {"description": "Stick input disabled", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost. This must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable RC stick override of auto and/or offboard modes", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold the autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "RC stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed is exceeded before detecting the freefall. This is a safety feature to ensure the drone does not turn on after accidental drop or a rapid movement before the throw. Set to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered. Failsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected. See COM_WIND_MAX to set the failsafe threshold. If enabled, it is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set RC loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}], "category": "Standard", "default": 1023, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 1023, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_A_IGATE", "shortDesc": "Gate size used for innovation consistency checks for range aid fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be played via buzzer or ESCs, if supported. The alarm will sound after a disarm, if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. -", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. It is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady state error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the current body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per second).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing. If set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits.", "max": 15.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in the loiter-down waypoint before the final approach. Otherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway. At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Geometry", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Geometry", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Launch detection", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Launch detection", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 0, "group": "FW Launch detection", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Not compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Launch detection", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "name": "NPFG_EN_MIN_GSP", "shortDesc": "Enable minimum forward ground speed maintaining excess wind handling logic", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW NPFG Control", "increment": 0.5, "longDesc": "The maximum value of the minimum forward ground speed that may be commanded by the track keeping excess wind handling logic. Commanded in full at the normalized track error fraction of the track error boundary and reduced to zero on track.", "max": 10.0, "min": 0.0, "name": "NPFG_GSP_MAX_TK", "shortDesc": "Maximum, minimum forward ground speed for track keeping in excess wind", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination. If false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "name": "NPFG_TRACK_KEEP", "shortDesc": "Enable track keeping excess wind handling logic", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Disabling this parameter further disables all other airspeed incrementation options.", "name": "NPFG_WIND_REG", "shortDesc": "Enable wind excess regulation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Path Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second. Applied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW Path Control", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Path Control", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 65.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Path Control", "increment": 0.5, "max": 30.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve. This value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of 0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX. Set negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX Set to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with the throttle set to FW_THR_MAX and the airspeed set to the trim value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced.", "max": 15.0, "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX.", "max": 5.0, "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers: - Rate controller: output scaling - Attitude controller: coordinated turn controller - Position controller: airspeed setpoint tracking, takeoff logic - VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW TECS", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 60.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 0.4, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Should be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW TECS", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout. If set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW TECS", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW TECS", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints. In manual modes: maximum climb rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW TECS", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle. A negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW TECS", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW TECS", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW TECS", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW TECS", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW TECS", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW TECS", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints. In manual modes: maximum sink rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW TECS", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control applies to speed vs height errors. 0 -> control height only 2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW TECS", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW TECS", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model of the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW TECS", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW TECS", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW TECS", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW TECS", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW TECS", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW TECS", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC to FW_LND_THRTC_SC*FW_T_ALT_TC. -1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW TECS", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Motor failure triggers only below this current value", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Threshold", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Motor failure triggers only above this throttle value.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Throttle Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 100, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Time Threshold", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "RC Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude FLW_TGT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port. In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. Set this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup.", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover (or Unicore primary) antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux) antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. (Note: the Unicore primary antenna is the one connected on the right as seen from the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use. Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. 'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures reported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. motor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and positive thrust of the tail rotor is expected to rotate the vehicle clockwise. Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction which is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag. This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch by aligning the lowest rotor drag with zero compensation. For symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle. For lift profile blades this is typically a command resulting in slightly negative collective blade angle. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy. This requires a symmetric setup where the servo horn is exactly centered with a 0 command. Setting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method. If set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state. Only used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing. Has to be set lower than the expected minimal speed for landing, which is either MPC_LAND_SPEED or MPC_LAND_CRWL. This is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 0, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 1, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 2, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Default to 1, switch to 2 if GCS sends version 2", "value": 0}, {"description": "Always use version 1", "value": 1}, {"description": "Always use version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers before takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive Decrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left and the right stick to the lower right at the same time until the gesture kills the actuators one-way. A negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "max": 3600, "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Mission", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 30.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure: gripper: NAV_CMD_DO_GRIPPER has released before continuing mission. winch: CMD_DO_WINCH has delivered before continuing mission. gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW has reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. Has no effect on mission validity. Set a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing. Then vehicle will loiter in this altitude until further command is received. Only applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to if not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing. Validity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in FW mode (e.g. for Loiter mode).", "max": 1000.0, "min": 25.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, excluding landing commands. Requires a distance sensor to be set up. Note: only prevents the vehicle from descending further, but does not force it to climb. Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this mode without specifying an altitude (e.g. through Loiter switch on RC). Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\"). Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion. Assumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation.", "max": 2, "min": 0, "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_PITCH", "shortDesc": "Offset for pitch channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_ROLL", "shortDesc": "Offset for roll channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_YAW", "shortDesc": "Offset for yaw channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_PITCH", "shortDesc": "Range of pitch channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration. This provides smoother flight but slightly worse tracking in position and auto modes. Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE 1 just deceleration 4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height 0: relative earth frame origin which may drift due to sensors 1: relative to ground (requires distance sensor) which changes with terrain variation. It will revert to relative earth frame if the distance to ground estimate becomes invalid. 2: relative to ground (requires distance sensor) when stationary and relative to earth frame when moving horizontally. The speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Does not apply to manual throttle and direct attitude piloting by stick.", "max": 1.0, "min": 0.0, "name": "MPC_HOLD_DZ", "shortDesc": "Deadzone for sticks in manual piloted modes", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle. A lower value leads to smoother motions but limits agility. Setting this to the maximum value essentially disables the limit. Only used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value between \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\" Value needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to \"MPC_LAND_SPEED\" Value needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available, limit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 1000.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this controls the maximum allowed horizontal displacement from the original landing point.", "min": 0.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed. The descend speed is amended: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode. Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized or Altitude mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode Setting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are: Direct velocity: Sticks directly map to velocity setpoints without smoothing. Also applies to vertical direction and Altitude mode. Useful for velocity control tuning. Acceleration based: Sticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode. Rescale to hover thrust estimate: Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output. No rescale: Directly map the stick 1:1 to the output. Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive. Rescale to hover thrust parameter: Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value. With MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). Used for initialization of the hover thrust estimator (see MPC_USE_HTE). The estimated hover thrust is used as base for zero vertical acceleration in altitude control. The hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority. With airmode enabled this parameters can be set to 0 while still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated. To avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes. Any higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller. This parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX. The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity. A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_XY_MAN_EXPO", "shortDesc": "Manual position control stick exponential curve sensitivity", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral Allows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes. Any higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_YAW_EXPO", "shortDesc": "Manual control stick yaw rotation exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_Z_MAN_EXPO", "shortDesc": "Manual control stick vertical exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.0, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration. 0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display. Resolution is limited by OSD to 15 discrete values. Negative values will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width. This is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "name": "PD_GRIPPER_EN", "rebootRequired": true, "shortDesc": "Enable Gripper actuation in Payload Deliverer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 3.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised. If the gripper has no feedback sensor, it will simply wait for this time before considering gripper actuation successful and publish a 'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC10_DZ", "shortDesc": "RC channel 10 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC11_DZ", "shortDesc": "RC channel 11 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC12_DZ", "shortDesc": "RC channel 12 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC13_DZ", "shortDesc": "RC channel 13 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC14_DZ", "shortDesc": "RC channel 14 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC15_DZ", "shortDesc": "RC channel 15 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC16_DZ", "shortDesc": "RC channel 16 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC17_DZ", "shortDesc": "RC channel 17 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC18_DZ", "shortDesc": "RC channel 18 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC1_DZ", "shortDesc": "RC channel 1 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC2_DZ", "shortDesc": "RC channel 2 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC3_DZ", "shortDesc": "RC channel 3 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC4_DZ", "shortDesc": "RC channel 4 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC5_DZ", "shortDesc": "RC channel 5 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC6_DZ", "shortDesc": "RC channel 6 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC7_DZ", "shortDesc": "RC channel 7 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC8_DZ", "shortDesc": "RC channel 8 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC9_DZ", "shortDesc": "RC channel 9 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. By default this is the throttle channel. Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, but below the minimum PWM value for the channel during normal operation. Note: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost (on receivers that use output a fixed signal value to report lost signal). If set to 0, the channel mapped to throttle is used. Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between the previous, current and next waypoint. Higher value -> smoother trajectory at the cost of how close the rover gets to the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RD_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr WP and curr-next WP interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RD_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the error between the desired and actual yaw. It is also used as the threshold whether the rover should come to a smooth stop at the next waypoint. This slow down effect is active if the angle between the line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the error between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given by the stick inputs. This can be understood as a deadzone for the combined stick inputs for forward/backwards and lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RM_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr waypoint and curr-next waypoint interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RM_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Rover Position Control (Deprecated)", "increment": 0.05, "longDesc": "Damping factor for L1 control.", "max": 0.9, "min": 0.6, "name": "GND_L1_DAMPING", "shortDesc": "L1 damping", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.1, "longDesc": "This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy).", "max": 50.0, "min": 1.0, "name": "GND_L1_DIST", "shortDesc": "L1 distance", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "longDesc": "This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation.", "max": 50.0, "min": 0.5, "name": "GND_L1_PERIOD", "shortDesc": "L1 period", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 150.0, "group": "Rover Position Control (Deprecated)", "max": 400.0, "min": 0.0, "name": "GND_MAN_Y_MAX", "shortDesc": "Max manual yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.7854, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians.", "max": 3.14159, "min": 0.0, "name": "GND_MAX_ANG", "shortDesc": "Maximum turn angle for Ackerman steering", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the derivative gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_D", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the integral gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_I", "shortDesc": "Speed Integral gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the maxim value the integral can reach to prevent wind-up.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_IMAX", "shortDesc": "Speed integral maximum value", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_MAX", "shortDesc": "Maximum ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the proportional gain for the speed closed loop controller", "max": 50.0, "min": 0.005, "name": "GND_SPEED_P", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is a gain to map the speed control output to the throttle linearly.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_THR_SC", "shortDesc": "Speed to throttle scaler", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_TRIM", "shortDesc": "Trim ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Rover Position Control (Deprecated)", "longDesc": "This allows the user to choose between closed loop gps speed or open loop cruise throttle speed", "max": 1, "min": 0, "name": "GND_SP_CTRL_MODE", "shortDesc": "Control mode for speed", "type": "Int32", "values": [{"description": "open loop control", "value": 0}, {"description": "close the loop with gps speed", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode", "max": 1.0, "min": 0.0, "name": "GND_THR_CRUISE", "shortDesc": "Cruise throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough", "max": 1.0, "min": 0.0, "name": "GND_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the minimum throttle % that can be used by the controller. Set to 0 for rover", "max": 1.0, "min": 0.0, "name": "GND_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.31, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "A value of 0.31 is typical for 1/10 RC cars.", "min": 0.0, "name": "GND_WHEEL_BASE", "shortDesc": "Distance from front axle to rear axle", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints in Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. For mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. The minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "longDesc": "0: airframe heading when takeoff is initiated 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF position defined by operator)", "max": 1, "min": 0, "name": "RWTO_HDG", "shortDesc": "Specifies which heading should be held during the runway takeoff ground roll", "type": "Int32", "values": [{"description": "Airframe", "value": 0}, {"description": "Runway", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Max throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Runway Takeoff", "increment": 0.1, "max": 100.0, "min": 1.0, "name": "RWTO_NPFG_PERIOD", "shortDesc": "NPFG period while steering on runway", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up). Must be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD). If set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the algorithm used for logfile encryption", "name": "SDLOG_ALGORITHM", "shortDesc": "Logfile Encryption algorithm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "XChaCha20", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key.", "max": 255, "min": 0, "name": "SDLOG_EXCH_KEY", "shortDesc": "Logfile Encryption key exchange key", "type": "Int32"}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY", "max": 255, "min": 0, "name": "SDLOG_KEY", "shortDesc": "Logfile Encryption key index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "disabled", "value": -1}, {"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 2047, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful when the battery is simulated externally and interfaced with PX4 through MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet. this number defines the (linear) conversion from voltage to Pascal (pa). For the MPXV7002DP this is 1000. NOTE: If the sensor always registers zero, try switching the static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors. This can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on the time derivative of the measured angular velocity, also known as the D-term filter in the rate controller. The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to increase IMU_GYRO_CUTOFF, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro. This only affects the angular velocity sent to the controllers, not the estimators. It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be allowed to publish at. This is the loop rate for the rate controller and outputs. Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities. Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (Roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (Pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (YAW) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance. The GPS selection logic waits until the primary receiver is available to send data to the EKF even if a secondary instance is already available. The secondary instance is then only used if the primary one times out. To have an equal priority of all the instances, set this parameter to -1 and the best receiver will be used. This parameter has no effect if blending is active.", "max": 1, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules. The greater this value, the slower the quad will move. Drag force function of velocity: D=-KDV*V. The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations. The greater this value, the slower the quad will rotate. Aerodynamic moment function of body rate: Ma=-KDW*W_B. This value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. If using FlightGear as a visual animation, this value can be tweaked such that the vehicle lies on the ground at takeoff. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment This value can be measured with a ruler. This corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller when the motor is running at full speed. This value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller when the motor is running at full speed. This value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Multicopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location Drift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot. WARNING: do not cut the power during an update process, otherwise you will have to recover using some alternative method (e.g. JTAG). Instructions: - Insert an SD card - Enable this parameter - Reboot the board (plug the power or send a reboot command) - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set), the 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses non-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. Note: this is only supported on boards with a separate calibration storage /fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands. WARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus F4 SD variants. If disabled, the preflight checks will not check for the presence of a barometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one. 1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor. If set to 0, the preflight checks will not check for the presence of an airspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Set to 'external HITL', if the system should perform as if it were a real vehicle (the only difference to a real system is then only the parameter value, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup against SYS_PARAM_VER, and if they do not match, parameters are reset and reloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_PITCH", "shortDesc": "Direct pitch input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_ROLL", "shortDesc": "Direct roll input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_THRUST", "shortDesc": "Direct thrust input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_YAW", "shortDesc": "Direct yaw input", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "name": "UUV_INPUT_MODE", "shortDesc": "Select Input Mode", "type": "Int32", "values": [{"description": "use Attitude Setpoints", "value": 0}, {"description": "Direct Feedthrough", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Position Control", "value": 0}, {"description": "Stabilization Mode", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected Agent IP address will be set and used. Decimal dot notation is not supported. IP address must be provided in int32 format. For example, 192.168.1.2 is mapped to -1062731518; 127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero. In a single agent - multi client configuration, each client must have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system. 0: Use the default configuration. 1: Restrict messages to localhost (use in combination with ROS_LOCALHOST_ONLY=1). 2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished. A value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished. A value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to pitch I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode. For standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind. Uses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead. Only active if demanded pitch is below VT_PITCH_MIN. Use VT_FWD_THRUST_SC to tune it. Descend mode is treated as Landing too. Only active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode. Enabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode and the altitude drops below this altitude (relative altitude above local origin), it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above Home if available, otherwise above the local origin) where triggering a quad-chute is possible. At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available. When airspeed is used, transition timeout is declared if airspeed does not reach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if VT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions. Zero will deactivate the slew rate limiting and thus produce an instant throttle rise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight. The check is only active if altitude is controlled and the vehicle is below the current altitude reference. The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current altitude reference. Set to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight in altitude-controlled flight modes. Active until 5s after completing transition to fixed-wing. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Miscellaneous", "name": "UUV_SKIP_CTRL", "shortDesc": "Skip the controller", "type": "Int32", "values": [{"description": "use the module's controller", "value": 0}, {"description": "skip the controller and feedthrough the setpoints", "value": 1}]}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file +{"parameters": [{"category": "Standard", "default": 75, "group": "UAVCAN Motor Parameters", "longDesc": "Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness.", "max": 250, "min": 10, "name": "ctl_bw", "shortDesc": "Speed controller bandwidth", "type": "Int32", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "UAVCAN Motor Parameters", "longDesc": "Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction.", "max": 1, "min": 0, "name": "ctl_dir", "shortDesc": "Reverse direction", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "UAVCAN Motor Parameters", "longDesc": "Speed (RPM) controller gain. Determines controller\n aggressiveness; units are amp-seconds per radian. Systems with\n higher rotational inertia (large props) will need gain increased;\n systems with low rotational inertia (small props) may need gain\n decreased. Higher values result in faster response, but may result\n in oscillation and excessive overshoot. Lower values result in a\n slower, smoother response.", "max": 1.0, "min": 0.0, "name": "ctl_gain", "shortDesc": "Speed (RPM) controller gain", "type": "Float", "units": "C/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.5, "group": "UAVCAN Motor Parameters", "longDesc": "Idle speed (e Hz)", "max": 100.0, "min": 0.0, "name": "ctl_hz_idle", "shortDesc": "Idle speed (e Hz)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 25, "group": "UAVCAN Motor Parameters", "longDesc": "Spin-up rate (e Hz/s)", "max": 1000, "min": 5, "name": "ctl_start_rate", "shortDesc": "Spin-up rate (e Hz/s)", "type": "Int32", "units": "1/s^2"}, {"category": "Standard", "default": 0, "group": "UAVCAN Motor Parameters", "longDesc": "Index of this ESC in throttle command messages.", "max": 15, "min": 0, "name": "esc_index", "shortDesc": "Index of this ESC in throttle command messages.", "type": "Int32"}, {"category": "Standard", "default": 20034, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status ID", "max": 1000000, "min": 1, "name": "id_ext_status", "shortDesc": "Extended status ID", "type": "Int32"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status interval (\u00b5s)", "max": 1000000, "min": 0, "name": "int_ext_status", "shortDesc": "Extended status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "ESC status interval (\u00b5s)", "max": 1000000, "name": "int_status", "shortDesc": "ESC status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 3, "default": 12.0, "group": "UAVCAN Motor Parameters", "longDesc": "Motor current limit in amps. This determines the maximum\n current controller setpoint, as well as the maximum allowable\n current setpoint slew rate. This value should generally be set to\n the continuous current rating listed in the motor\u2019s specification\n sheet, or set equal to the motor\u2019s specified continuous power\n divided by the motor voltage limit.", "max": 80.0, "min": 1.0, "name": "mot_i_max", "shortDesc": "Motor current limit in amps", "type": "Float", "units": "A"}, {"category": "Standard", "default": 2300, "group": "UAVCAN Motor Parameters", "longDesc": "Motor Kv in RPM per volt. This can be taken from the motor\u2019s\n specification sheet; accuracy will help control performance but\n some deviation from the specified value is acceptable.", "max": 4000, "min": 0, "name": "mot_kv", "shortDesc": "Motor Kv in RPM per volt", "type": "Int32", "units": "rpm/V"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor inductance in henries. This is measured on start-up.", "name": "mot_ls", "shortDesc": "READ ONLY: Motor inductance in henries.", "type": "Float", "units": "H"}, {"category": "Standard", "default": 14, "group": "UAVCAN Motor Parameters", "longDesc": "Number of motor poles. Used to convert mechanical speeds to\n electrical speeds. This number should be taken from the motor\u2019s\n specification sheet.", "max": 40, "min": 2, "name": "mot_num_poles", "shortDesc": "Number of motor poles.", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor resistance in ohms. This is measured on start-up. When\n tuning a new motor, check that this value is approximately equal\n to the value shown in the motor\u2019s specification sheet.", "name": "mot_rs", "shortDesc": "READ ONLY: Motor resistance in ohms", "type": "Float", "units": "Ohm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "UAVCAN Motor Parameters", "longDesc": "Acceleration limit (V)", "max": 1.0, "min": 0.01, "name": "mot_v_accel", "shortDesc": "Acceleration limit (V)", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 3, "default": 14.8, "group": "UAVCAN Motor Parameters", "longDesc": "Motor voltage limit in volts. The current controller\u2019s\n commanded voltage will never exceed this value. Note that this may\n safely be above the nominal voltage of the motor; to determine the\n actual motor voltage limit, divide the motor\u2019s rated power by the\n motor current limit.", "min": 0.0, "name": "mot_v_max", "shortDesc": "Motor voltage limit in volts", "type": "Float", "units": "V"}, {"category": "Standard", "default": 2, "group": "UAVCAN GNSS", "longDesc": "Dynamic model used in the GNSS positioning engine. 0 \u2013\n Automotive, 1 \u2013 Sea, 2 \u2013 Airborne.\n ", "max": 2, "min": 0, "name": "gnss.dyn_model", "shortDesc": "GNSS dynamic model", "type": "Int32", "values": [{"description": "Automotive", "value": 0}, {"description": "Sea", "value": 1}, {"description": "Airborne", "value": 2}]}, {"category": "Standard", "default": 1, "group": "UAVCAN GNSS", "longDesc": "Broadcast the old (deprecated) GNSS fix message\n uavcan.equipment.gnss.Fix alongside the new alternative\n uavcan.equipment.gnss.Fix2. It is recommended to\n disable this feature to reduce the CAN bus traffic.\n ", "max": 1, "min": 0, "name": "gnss.old_fix_msg", "shortDesc": "Broadcast old GNSS fix message", "type": "Int32", "values": [{"description": "Fix2", "value": 0}, {"description": "Fix and Fix2", "value": 1}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the dimensionality of\n the GNSS solution is less than this value. 3 for the full (3D)\n solution, 2 for planar (2D) solution, 1 for time-only solution,\n 0 disables the feature.\n ", "max": 3, "min": 0, "name": "gnss.warn_dimens", "shortDesc": "device health warning", "type": "Int32", "values": [{"description": "disables the feature", "value": 0}, {"description": "time-only solution", "value": 1}, {"description": "planar (2D) solution", "value": 2}, {"description": "full (3D) solution", "value": 3}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "name": "gnss.warn_sats", "shortDesc": "", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "max": 1000000, "min": 0, "name": "uavcan.pubp-pres", "shortDesc": "", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \". Example \"PX4 \" -> 1347957792 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel. Note: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change. Triggers when the airspeed change within this window is negative while throttle increases and the vehicle pitches down. Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions. Relies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) and measured airspeed. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good. Set to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.55, "group": "Airspeed Validator", "longDesc": "The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.001, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for synthetic airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision. Set to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using an RC AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio", "name": "FW_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "This parameter scales the signal sent to the rate controller during system identification.", "max": 6.0, "min": 0.1, "name": "FW_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio", "name": "MC_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation, which in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low. This has to be lower than the critical threshold. This threshold commonly will trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low. This has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events the specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification. Setting this parameter to 782090 will disable the startup tune, while keeping all others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected checks in the commander, setting it to 0 keeps them enabled (recommended). We are generally recommending to not fly with the USB link connected and production vehicles should set this parameter to zero to prevent users from flying USB powered. However, for R&D purposes it has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_* parameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods: - one arm: request authorization and arm when authorization is received - two step arm: 1st arm command request an authorization and 2nd arm command arm the drone if authorized Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer. Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited. A negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the SD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition. 1: Arming/disarming triggers when holding the momentary button down for COM_RC_ARM_HYST like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Measures taken when a check defined by EKF2_GPS_CHECK is failing.", "name": "COM_ARM_WO_GPS", "shortDesc": "GPS preflight check", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Disabled", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed 1: Allow disarming in multicopter flight in modes where the thrust is directly controlled by thr throttle stick e.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which datalink loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature (see COM_RC_OVERRIDE). Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed).", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below the estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any auto mode other than RTL or Land. Taking over in any manual mode is still possible. Starting from 90% of the maximum flight time, a warning message will be sent every 1 minute with the remaining time until automatic RTL. Set to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss' flag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode.", "name": "COM_POSCTL_NAVL", "shortDesc": "Position mode navigation loss response", "type": "Int32", "values": [{"description": "Altitude mode", "value": 0}, {"description": "Land mode (descend)", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Set to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold. See COM_POS_LOW_EPH to set the failsafe threshold. The failsafe action is only executed if the vehicle is in auto mission or auto loiter mode, otherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold. Local position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT), and a high failsafe threshold (COM_POS_FS_EPH). Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed in which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which RC loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "RC loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Commander", "longDesc": "The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.", "max": 1500, "min": 100, "name": "COM_RC_ARM_HYST", "shortDesc": "RC input arm/disarm command duration", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input.", "max": 4, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "RC control input mode", "type": "Int32", "values": [{"description": "RC Transmitter only", "value": 0}, {"description": "Joystick only", "value": 1}, {"description": "RC and Joystick with fallback", "value": 2}, {"description": "RC or Joystick keep first", "value": 3}, {"description": "Stick input disabled", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost. This must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable RC stick override of auto and/or offboard modes", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold the autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "RC stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed is exceeded before detecting the freefall. This is a safety feature to ensure the drone does not turn on after accidental drop or a rapid movement before the throw. Set to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered. Failsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected. See COM_WIND_MAX to set the failsafe threshold. If enabled, it is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set RC loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}], "category": "Standard", "default": 1023, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 1023, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_A_IGATE", "shortDesc": "Gate size used for innovation consistency checks for range aid fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be played via buzzer or ESCs, if supported. The alarm will sound after a disarm, if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. -", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. It is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady state error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the current body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per second).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing. If set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits.", "max": 15.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in the loiter-down waypoint before the final approach. Otherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway. At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Geometry", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Geometry", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Launch detection", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Launch detection", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 0, "group": "FW Launch detection", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Not compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Launch detection", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "name": "NPFG_EN_MIN_GSP", "shortDesc": "Enable minimum forward ground speed maintaining excess wind handling logic", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW NPFG Control", "increment": 0.5, "longDesc": "The maximum value of the minimum forward ground speed that may be commanded by the track keeping excess wind handling logic. Commanded in full at the normalized track error fraction of the track error boundary and reduced to zero on track.", "max": 10.0, "min": 0.0, "name": "NPFG_GSP_MAX_TK", "shortDesc": "Maximum, minimum forward ground speed for track keeping in excess wind", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination. If false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "name": "NPFG_TRACK_KEEP", "shortDesc": "Enable track keeping excess wind handling logic", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Disabling this parameter further disables all other airspeed incrementation options.", "name": "NPFG_WIND_REG", "shortDesc": "Enable wind excess regulation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Path Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second. Applied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW Path Control", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Path Control", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 65.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Path Control", "increment": 0.5, "max": 30.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve. This value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of 0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX. Set negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX Set to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with the throttle set to FW_THR_MAX and the airspeed set to the trim value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced.", "max": 15.0, "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX.", "max": 5.0, "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers: - Rate controller: output scaling - Attitude controller: coordinated turn controller - Position controller: airspeed setpoint tracking, takeoff logic - VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW TECS", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 60.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 0.4, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Should be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW TECS", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout. If set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW TECS", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW TECS", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints. In manual modes: maximum climb rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW TECS", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle. A negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW TECS", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW TECS", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW TECS", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW TECS", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW TECS", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW TECS", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints. In manual modes: maximum sink rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW TECS", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control applies to speed vs height errors. 0 -> control height only 2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW TECS", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW TECS", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model of the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW TECS", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW TECS", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW TECS", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW TECS", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW TECS", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW TECS", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC to FW_LND_THRTC_SC*FW_T_ALT_TC. -1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW TECS", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Motor failure triggers only below this current value", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Threshold", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Motor failure triggers only above this throttle value.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Throttle Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 100, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Time Threshold", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "RC Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude FLW_TGT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port. In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. Set this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup.", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover (or Unicore primary) antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux) antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. (Note: the Unicore primary antenna is the one connected on the right as seen from the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use. Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. 'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures reported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. motor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and positive thrust of the tail rotor is expected to rotate the vehicle clockwise. Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction which is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag. This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch by aligning the lowest rotor drag with zero compensation. For symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle. For lift profile blades this is typically a command resulting in slightly negative collective blade angle. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy. This requires a symmetric setup where the servo horn is exactly centered with a 0 command. Setting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method. If set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state. Only used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing. Has to be set lower than the expected minimal speed for landing, which is either MPC_LAND_SPEED or MPC_LAND_CRWL. This is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 0, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 1, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 2, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Default to 1, switch to 2 if GCS sends version 2", "value": 0}, {"description": "Always use version 1", "value": 1}, {"description": "Always use version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers before takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive Decrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left and the right stick to the lower right at the same time until the gesture kills the actuators one-way. A negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "max": 3600, "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Mission", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 30.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure: gripper: NAV_CMD_DO_GRIPPER has released before continuing mission. winch: CMD_DO_WINCH has delivered before continuing mission. gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW has reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. Has no effect on mission validity. Set a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing. Then vehicle will loiter in this altitude until further command is received. Only applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to if not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing. Validity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in FW mode (e.g. for Loiter mode).", "max": 1000.0, "min": 25.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, excluding landing commands. Requires a distance sensor to be set up. Note: only prevents the vehicle from descending further, but does not force it to climb. Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this mode without specifying an altitude (e.g. through Loiter switch on RC). Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\"). Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion. Assumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation.", "max": 2, "min": 0, "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_PITCH", "shortDesc": "Offset for pitch channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_ROLL", "shortDesc": "Offset for roll channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_YAW", "shortDesc": "Offset for yaw channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_PITCH", "shortDesc": "Range of pitch channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration. This provides smoother flight but slightly worse tracking in position and auto modes. Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE 1 just deceleration 4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height 0: relative earth frame origin which may drift due to sensors 1: relative to ground (requires distance sensor) which changes with terrain variation. It will revert to relative earth frame if the distance to ground estimate becomes invalid. 2: relative to ground (requires distance sensor) when stationary and relative to earth frame when moving horizontally. The speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Does not apply to manual throttle and direct attitude piloting by stick.", "max": 1.0, "min": 0.0, "name": "MPC_HOLD_DZ", "shortDesc": "Deadzone for sticks in manual piloted modes", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle. A lower value leads to smoother motions but limits agility. Setting this to the maximum value essentially disables the limit. Only used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value between \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\" Value needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to \"MPC_LAND_SPEED\" Value needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available, limit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 1000.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this controls the maximum allowed horizontal displacement from the original landing point.", "min": 0.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed. The descend speed is amended: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode. Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized or Altitude mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode Setting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are: Direct velocity: Sticks directly map to velocity setpoints without smoothing. Also applies to vertical direction and Altitude mode. Useful for velocity control tuning. Acceleration based: Sticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode. Rescale to hover thrust estimate: Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output. No rescale: Directly map the stick 1:1 to the output. Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive. Rescale to hover thrust parameter: Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value. With MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). Used for initialization of the hover thrust estimator (see MPC_USE_HTE). The estimated hover thrust is used as base for zero vertical acceleration in altitude control. The hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority. With airmode enabled this parameters can be set to 0 while still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated. To avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes. Any higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller. This parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX. The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity. A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_XY_MAN_EXPO", "shortDesc": "Manual position control stick exponential curve sensitivity", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral Allows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes. Any higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_YAW_EXPO", "shortDesc": "Manual control stick yaw rotation exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_Z_MAN_EXPO", "shortDesc": "Manual control stick vertical exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.0, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration. 0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display. Resolution is limited by OSD to 15 discrete values. Negative values will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width. This is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "name": "PD_GRIPPER_EN", "rebootRequired": true, "shortDesc": "Enable Gripper actuation in Payload Deliverer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 3.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised. If the gripper has no feedback sensor, it will simply wait for this time before considering gripper actuation successful and publish a 'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC10_DZ", "shortDesc": "RC channel 10 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC11_DZ", "shortDesc": "RC channel 11 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC12_DZ", "shortDesc": "RC channel 12 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC13_DZ", "shortDesc": "RC channel 13 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC14_DZ", "shortDesc": "RC channel 14 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC15_DZ", "shortDesc": "RC channel 15 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC16_DZ", "shortDesc": "RC channel 16 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC17_DZ", "shortDesc": "RC channel 17 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC18_DZ", "shortDesc": "RC channel 18 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC1_DZ", "shortDesc": "RC channel 1 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC2_DZ", "shortDesc": "RC channel 2 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC3_DZ", "shortDesc": "RC channel 3 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC4_DZ", "shortDesc": "RC channel 4 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC5_DZ", "shortDesc": "RC channel 5 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC6_DZ", "shortDesc": "RC channel 6 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC7_DZ", "shortDesc": "RC channel 7 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC8_DZ", "shortDesc": "RC channel 8 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC9_DZ", "shortDesc": "RC channel 9 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. By default this is the throttle channel. Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, but below the minimum PWM value for the channel during normal operation. Note: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost (on receivers that use output a fixed signal value to report lost signal). If set to 0, the channel mapped to throttle is used. Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between the previous, current and next waypoint. Higher value -> smoother trajectory at the cost of how close the rover gets to the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RD_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr WP and curr-next WP interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RD_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the error between the desired and actual yaw. It is also used as the threshold whether the rover should come to a smooth stop at the next waypoint. This slow down effect is active if the angle between the line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the error between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given by the stick inputs. This can be understood as a deadzone for the combined stick inputs for forward/backwards and lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RM_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr waypoint and curr-next waypoint interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RM_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Rover Position Control (Deprecated)", "increment": 0.05, "longDesc": "Damping factor for L1 control.", "max": 0.9, "min": 0.6, "name": "GND_L1_DAMPING", "shortDesc": "L1 damping", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.1, "longDesc": "This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy).", "max": 50.0, "min": 1.0, "name": "GND_L1_DIST", "shortDesc": "L1 distance", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "longDesc": "This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation.", "max": 50.0, "min": 0.5, "name": "GND_L1_PERIOD", "shortDesc": "L1 period", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 150.0, "group": "Rover Position Control (Deprecated)", "max": 400.0, "min": 0.0, "name": "GND_MAN_Y_MAX", "shortDesc": "Max manual yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.7854, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians.", "max": 3.14159, "min": 0.0, "name": "GND_MAX_ANG", "shortDesc": "Maximum turn angle for Ackerman steering", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the derivative gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_D", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the integral gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_I", "shortDesc": "Speed Integral gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the maxim value the integral can reach to prevent wind-up.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_IMAX", "shortDesc": "Speed integral maximum value", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_MAX", "shortDesc": "Maximum ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the proportional gain for the speed closed loop controller", "max": 50.0, "min": 0.005, "name": "GND_SPEED_P", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is a gain to map the speed control output to the throttle linearly.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_THR_SC", "shortDesc": "Speed to throttle scaler", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_TRIM", "shortDesc": "Trim ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Rover Position Control (Deprecated)", "longDesc": "This allows the user to choose between closed loop gps speed or open loop cruise throttle speed", "max": 1, "min": 0, "name": "GND_SP_CTRL_MODE", "shortDesc": "Control mode for speed", "type": "Int32", "values": [{"description": "open loop control", "value": 0}, {"description": "close the loop with gps speed", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode", "max": 1.0, "min": 0.0, "name": "GND_THR_CRUISE", "shortDesc": "Cruise throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough", "max": 1.0, "min": 0.0, "name": "GND_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the minimum throttle % that can be used by the controller. Set to 0 for rover", "max": 1.0, "min": 0.0, "name": "GND_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.31, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "A value of 0.31 is typical for 1/10 RC cars.", "min": 0.0, "name": "GND_WHEEL_BASE", "shortDesc": "Distance from front axle to rear axle", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints in Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. For mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. The minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "longDesc": "0: airframe heading when takeoff is initiated 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF position defined by operator)", "max": 1, "min": 0, "name": "RWTO_HDG", "shortDesc": "Specifies which heading should be held during the runway takeoff ground roll", "type": "Int32", "values": [{"description": "Airframe", "value": 0}, {"description": "Runway", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Max throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Runway Takeoff", "increment": 0.1, "max": 100.0, "min": 1.0, "name": "RWTO_NPFG_PERIOD", "shortDesc": "NPFG period while steering on runway", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up). Must be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD). If set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the algorithm used for logfile encryption", "name": "SDLOG_ALGORITHM", "shortDesc": "Logfile Encryption algorithm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "XChaCha20", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key.", "max": 255, "min": 0, "name": "SDLOG_EXCH_KEY", "shortDesc": "Logfile Encryption key exchange key", "type": "Int32"}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY", "max": 255, "min": 0, "name": "SDLOG_KEY", "shortDesc": "Logfile Encryption key index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "disabled", "value": -1}, {"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 2047, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful when the battery is simulated externally and interfaced with PX4 through MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet. this number defines the (linear) conversion from voltage to Pascal (pa). For the MPXV7002DP this is 1000. NOTE: If the sensor always registers zero, try switching the static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors. This can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on the time derivative of the measured angular velocity, also known as the D-term filter in the rate controller. The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to increase IMU_GYRO_CUTOFF, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro. This only affects the angular velocity sent to the controllers, not the estimators. It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be allowed to publish at. This is the loop rate for the rate controller and outputs. Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities. Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (Roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (Pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (YAW) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance. The GPS selection logic waits until the primary receiver is available to send data to the EKF even if a secondary instance is already available. The secondary instance is then only used if the primary one times out. To have an equal priority of all the instances, set this parameter to -1 and the best receiver will be used. This parameter has no effect if blending is active.", "max": 1, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules. The greater this value, the slower the quad will move. Drag force function of velocity: D=-KDV*V. The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations. The greater this value, the slower the quad will rotate. Aerodynamic moment function of body rate: Ma=-KDW*W_B. This value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. If using FlightGear as a visual animation, this value can be tweaked such that the vehicle lies on the ground at takeoff. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment This value can be measured with a ruler. This corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller when the motor is running at full speed. This value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller when the motor is running at full speed. This value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Quadcopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}, {"description": "Hexacopter", "value": 4}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location Drift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot. WARNING: do not cut the power during an update process, otherwise you will have to recover using some alternative method (e.g. JTAG). Instructions: - Insert an SD card - Enable this parameter - Reboot the board (plug the power or send a reboot command) - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set), the 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses non-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. Note: this is only supported on boards with a separate calibration storage /fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands. WARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus F4 SD variants. If disabled, the preflight checks will not check for the presence of a barometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one. 1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor. If set to 0, the preflight checks will not check for the presence of an airspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Set to 'external HITL', if the system should perform as if it were a real vehicle (the only difference to a real system is then only the parameter value, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup against SYS_PARAM_VER, and if they do not match, parameters are reset and reloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_PITCH", "shortDesc": "Direct pitch input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_ROLL", "shortDesc": "Direct roll input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_THRUST", "shortDesc": "Direct thrust input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_YAW", "shortDesc": "Direct yaw input", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "name": "UUV_INPUT_MODE", "shortDesc": "Select Input Mode", "type": "Int32", "values": [{"description": "use Attitude Setpoints", "value": 0}, {"description": "Direct Feedthrough", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Position Control", "value": 0}, {"description": "Stabilization Mode", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected Agent IP address will be set and used. Decimal dot notation is not supported. IP address must be provided in int32 format. For example, 192.168.1.2 is mapped to -1062731518; 127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero. In a single agent - multi client configuration, each client must have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system. 0: Use the default configuration. 1: Restrict messages to localhost (use in combination with ROS_LOCALHOST_ONLY=1). 2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished. A value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished. A value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to pitch I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode. For standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind. Uses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead. Only active if demanded pitch is below VT_PITCH_MIN. Use VT_FWD_THRUST_SC to tune it. Descend mode is treated as Landing too. Only active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode. Enabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode and the altitude drops below this altitude (relative altitude above local origin), it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above Home if available, otherwise above the local origin) where triggering a quad-chute is possible. At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available. When airspeed is used, transition timeout is declared if airspeed does not reach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if VT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions. Zero will deactivate the slew rate limiting and thus produce an instant throttle rise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight. The check is only active if altitude is controlled and the vehicle is below the current altitude reference. The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current altitude reference. Set to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight in altitude-controlled flight modes. Active until 5s after completing transition to fixed-wing. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Miscellaneous", "name": "UUV_SKIP_CTRL", "shortDesc": "Skip the controller", "type": "Int32", "values": [{"description": "use the module's controller", "value": 0}, {"description": "skip the controller and feedthrough the setpoints", "value": 1}]}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file diff --git a/docs/public/middleware/graph_full.json b/docs/public/middleware/graph_full.json index ebce6e1a1d..a609e0877f 100644 --- a/docs/public/middleware/graph_full.json +++ b/docs/public/middleware/graph_full.json @@ -1 +1 @@ -{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#5cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#5c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41b8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_status", "name": "internal_combustion_engine_status", "type": "topic", "color": "#d88741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d895", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#41cfd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#41a0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d8bc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84152", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41acd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d84187", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d88d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d86441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance_fused", "name": "obstacle_distance_fused", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#79d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d841aa", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d84164", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d8ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#4189d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#4142d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#a8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d841cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d8415e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d8cd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#4195d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d84158", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d89e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_serial_passthru", "name": "esc_serial_passthru", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#4441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#a841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d841bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d8b8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#d84641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41d8a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#4177d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d89341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#41d8cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41a6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#417dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d84193", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#d8aa41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d842", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d8b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#6241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d85241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d85841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#41b2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8418d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d84c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#62d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#41d848", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#4148d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#7341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#73d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d87d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#41d889", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#7941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d84146", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41d877", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#ba41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#d8419e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#44d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#d85e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d8414c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#bad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#41d89b", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#44d841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#d8419e", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d8be", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#ba41d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#85d841", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#d84641", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#4177d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#7f41d8", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#a2d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#41d848", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d8be", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#ba41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#85d841", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#bad841", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#bad841", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#41d848", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8418d", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#d84c41", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#d841b0", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#41d8ca", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#ccd841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#41d8ca", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d88d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#41d848", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#4189d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8418d", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#68d841", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance_fused", "color": "#d8b041", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#d8d341", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#417dd8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#ba41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#ae41d8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#44d841", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#bad841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41d8be", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#41d8d5", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#b4d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#d84181", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#d8a441", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#4a41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#41d860", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#41d84e", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#8b41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#ae41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#4ad841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#417dd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#4160d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d8d341", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d7d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84175", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d84164", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d8ac", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#d85e41", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#9d41d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#aed841", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#a8d841", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#aed841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#4142d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d8b8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#4142d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#4142d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d87b41", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#41d8d5", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#b4d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#d8a441", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#4a41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#41d860", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#41d84e", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#41d5d8", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#ccd841", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#a841d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#41a0d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d8c841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#5c41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d87541", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d1d841", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#4171d8", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#8541d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#79d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#68d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#d87041", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#ba41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#41a6d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#41a0d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d8c841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d1d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#5c41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#79d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#d84c41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#41a0d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#41d877", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#416cd8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d8c841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d1d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#bad841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#5c41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#ba41d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#7f41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#5cd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#a241d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#41b2d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d842", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#b441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d841b6", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#418fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d871", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d84187", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d89b", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d84164", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d8414c", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#a8d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d88141", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41d854", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#41b2d8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#9141d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d85841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d84158", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#418fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#50d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d86441", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#4148d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#6841d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#7341d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#4441d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d84170", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#7341d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d84199", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41cad8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#41b2d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8a6", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41acd8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41acd8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d84181", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#4142d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84152", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#4195d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#d8aa41", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#41d889", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d841c8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#417dd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#8bd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87541", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d841a4", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d84193", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#c641d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#c6d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#7341d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#d89941", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#d89e41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#d84146", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#41b8d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#d84181", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d841aa", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d87b41", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_status", "color": "#d88741", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#56d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#4183d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d84164", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#ae41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#d7d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#8541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#79d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d84c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_esc_serial_passthru", "color": "#6ed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_obstacle_distance", "color": "#68d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#9741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#73d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#41cfd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d86a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d87041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#ba41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d89341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#c041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41d854", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41acd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d841cd", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d841c2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d841bc", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8b641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d87d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8c241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#415ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d8cd41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d8d341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d895", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#414ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d89b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d84164", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#4142d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d8416a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d8b2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#4441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d8be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#41d8c4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d8414c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#5641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#41d8cf", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d8415e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#8541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d8bc41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#91d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41bed8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#4154d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#6241d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d841d3", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#62d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41acd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d741d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d866", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d87b41", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#97d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d88f", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#7941d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41d8a0", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#c6d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#4441d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41acd8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d85241", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d84170", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8a6", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#41d8d5", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#b4d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#d8a441", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#4a41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#41d860", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#41d84e", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d8417b", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d8d341", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#41b2d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#d88141", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#73d841", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#41d8cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#41d85a", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#6e41d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d84193", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#41a6d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#41d8ca", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d8d341", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#41b2d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d8417b", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#d8419e", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#d8416a", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#7941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#7341d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#d8417b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d8417b", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d8be", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d8d341", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d84164", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84175", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#5041d8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#418fd8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#41d877", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#a8d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#7f41d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#ba41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#41b2d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41d88f", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#a2d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#d85e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#41b2d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d8417b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#d8417b", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d8be", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d85841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#9141d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#ba41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#d85841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d85841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8416a", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d85841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#41b2d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#41b2d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#41b2d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#41b2d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41d88f", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#d841b0", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#ba41d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d84164", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d8d341", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#5041d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d84175", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#41b2d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#41d8ca", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#7941d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#7341d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#9141d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#9741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d85841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#d85e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#41b2d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#4195d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d841c2", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#418fd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41d88f", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d8cd41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84175", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d8416a", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d8b8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#a8d841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#9dd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#d8417b", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#7941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#7341d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#9141d8", "style": "normal"}, {"source": "t_esc_serial_passthru", "target": "m_voxl_esc", "color": "#6ed841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#d85e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#41b2d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#6241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#d841aa", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d88f", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84175", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#41b2d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#44d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#d8d341", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#68d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d8417b", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#41c4d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d8d341", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#41b2d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#41b2d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#7941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#7941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#7941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#7941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#7941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#7941d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#8bd841", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#41d8d5", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#d84199", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#4441d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#b4d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#d8a441", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#d8aa41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d84158", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#41d860", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#d841cd", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#d8d341", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#4a41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#d84187", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#41d84e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d84175", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#c641d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#79d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#41d889", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d88f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#9d41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#97d841", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#a841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#41b2d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#417dd8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#8bd841", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87541", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d85a", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#41d88f", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d84c41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84175", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d84164", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#4166d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#4441d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d85241", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d841c8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#97d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d84187", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#41b2d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84175", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#73d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#41c4d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41d8a0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#41b2d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d883", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41acd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d8d341", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41acd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#4142d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d84199", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#a8d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#97d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#41d8d5", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#d84199", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#4441d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#b4d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#d8a441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d84158", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#4a41d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#41d860", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#d841cd", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#d8d341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#d84187", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#41d84e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d84175", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8418d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d8d341", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d84164", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#5c41d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#41a6d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#41d88f", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#41b2d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#56d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d1d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#7341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#d84199", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d8b8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#9141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#41d88f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#4195d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#56d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#41bed8", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#d85e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#6241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d8417b", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#41a6d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#41d88f", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#41b2d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#41a0d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d84164", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#7f41d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#8b41d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d84193", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#a8d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d8414c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d88f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#9d41d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#a241d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#418fd8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41b8d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#41b2d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d84181", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84175", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d88141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d88f", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#41b2d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#4183d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#8b41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#73d841", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#62d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d85841", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41cad8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#41c4d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#50d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#ae41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#41b2d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#41d848", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#4ad841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d842", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#b441d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#44d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#ba41d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d89341", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#c041d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d85a", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d841cd", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d86c", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d87d", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#4183d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d871", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41d877", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#417dd8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d841a4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d84199", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d8d341", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#414ed8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41d8a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84175", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8a6", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d84164", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#ccd841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d8ac", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d8417b", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#a8d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#97d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#5041d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#41d877", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#41b2d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d841c8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#73d841", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#41d8cf", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41acd8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d85241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84175", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41cad8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d84199", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8a6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d8d341", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#4441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d84164", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d84199", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#4441d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d8d341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#d84187", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#4142d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d84199", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d84158", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#4166d8", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#bad841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#41d883", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d84158", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d741d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d86441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#41b2d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8a6", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d87b41", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#41d889", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#73d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d841c8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d841bc", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#41c4d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#41d8ca", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#417dd8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#414ed8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41d8a0", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#4142d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d8d341", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d89b", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#d84164", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#d84199", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#4441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#a8d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#d8d341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#d84187", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d84175", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#d8417b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#d84199", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#bad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#416cd8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#79d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#41d88f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#d8d341", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#8bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d84175", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d85841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d86a41", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d88141", "style": "normal"}, {"source": "t_internal_combustion_engine_status", "target": "m_mavlink", "color": "#d88741", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d88d41", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d89e41", "style": "normal"}, {"source": "t_obstacle_distance_fused", "target": "m_mavlink", "color": "#d8b041", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8b641", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d8bc41", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d7d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#bad841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#a8d841", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#91d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#97d841", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#85d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#4ad841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d842", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d85a", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d87d", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d871", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#41d889", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8a6", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41d8a0", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d8be", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41acd8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41a6d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#41a0d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#418fd8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#4189d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#4183d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#4154d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#414ed8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#4148d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#4142d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#5641d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#5c41d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#6841d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#7f41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#8541d8", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#8b41d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#ae41d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#ba41d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#c041d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d84199", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8418d", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d84193", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d84187", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#d84181", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d84164", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d8415e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d84158", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d8414c", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d84146", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#41b2d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d841aa", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#41d8ca", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d84164", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#7fd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#8541d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d88f", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#419bd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d84187", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d87041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d84199", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d8b2", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d88f", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#41b2d8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41cfd8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#41b2d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d8d341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d84187", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d84158", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#97d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d84146", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#4166d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#a8d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d84146", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d8d341", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#ae41d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#4ad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#41b2d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d841aa", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84175", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#73d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d88f", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#41c4d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#41d87d", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#4441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d84158", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d84170", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#6e41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8a6", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#415ad8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#41d8d5", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#d84199", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#4441d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#b4d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#d8a441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d84158", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#4a41d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#41d860", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#d841cd", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#d8d341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#d84187", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#41d84e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#79d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d8d341", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#8bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84175", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#41b2d8", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#7341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#41d842", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8419e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_status", "name": "internal_combustion_engine_status", "type": "topic", "color": "#d84164", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84146", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d85841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d85e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d8a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d88d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d841aa", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d84152", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#62d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#41d848", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d877", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#41a0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance_fused", "name": "obstacle_distance_fused", "type": "topic", "color": "#5c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#7941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#ba41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41a6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#a841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41d8ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8aa41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#73d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d8b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_serial_passthru", "name": "esc_serial_passthru", "type": "topic", "color": "#4148d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#d841cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d89e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#79d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#5cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d87d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d88741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#d8cd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#6241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d84c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d841bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8414c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#44d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d889", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d8a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41cfd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41b2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#4189d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#d8415e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#417dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#4177d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d8418d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d85241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#a8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#4142d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#4441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#bad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41acd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4195d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d84187", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d8cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d84193", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d86441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d84158", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41b8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d8b8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d89341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d895", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d8bc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#44d841", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d84141", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#41d883", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#414ed8", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#d8cd41", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#97d841", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#d89e41", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d84187", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d8d341", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#414ed8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d8d341", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#41d85a", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#4142d8", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#41cad8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d89941", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d89941", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41acd8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d8a441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#a841d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d8d341", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#41d85a", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance_fused", "color": "#5c41d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#6241d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#d841c8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#d84c41", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#d84141", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#62d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#41a0d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#41d8be", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#d841cd", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#41d848", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#d841b6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d84c41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841c8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d841bc", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d88d41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d895", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#a241d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#85d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#7fd841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d8d5", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#73d841", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4154d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d88f", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4154d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d87d", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#62d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#41a0d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#41d8be", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#d841cd", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#41d848", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#d841b6", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#b441d8", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#41acd8", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d84199", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#c6d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8419e", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41d5d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#41d842", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7341d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d7d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d85841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#41d842", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d8419e", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#6241d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#c6d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7341d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#d84152", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#56d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#41d842", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d8419e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#4142d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#c6d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7341d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#6ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#50d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#418fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d87541", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#44d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d841c2", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#4177d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d89e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d84175", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#6e41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d88f", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#9dd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#9141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d84158", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#91d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#6ed841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d85e41", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d85241", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d741d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d8418d", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d8c841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d87b41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#4177d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d89341", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#41d86c", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d8b2", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#bad841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#5641d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#bad841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d877", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#4177d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d84e", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#b4d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#a2d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84641", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d8ca", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4ad841", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41d5d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841c8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#79d841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#ccd841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#415ad8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#41d860", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#41d871", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#ba41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#7941d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#bad841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84146", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_status", "color": "#d84164", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d8b8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d84c41", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#7fd841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#d841bc", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d85841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#56d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d87041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#44d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#4160d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d89e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d89341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d841aa", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d866", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#4142d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_esc_serial_passthru", "color": "#4148d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d84170", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_obstacle_distance", "color": "#6241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d889", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#6841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d8a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d8a0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41d8ac", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#41d8b2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#8bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d84152", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41d5d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#c041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8414c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#73d841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d1d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d85841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#ae41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#d8415e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#8b41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d88741", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#9741d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#4441d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41d854", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d8b041", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8aa41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#5cd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d8417b", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d8b2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#41d86c", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84146", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#5641d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#62d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#41a0d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#41d8be", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#d841cd", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#41d848", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#d841b6", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#7fd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#d8418d", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#4183d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#68d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#ccd841", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#41b8d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d841a4", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#416cd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d87d", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#41d883", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#4166d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#41d8d5", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#41d87d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41b2d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#8541d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#416cd8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#6ed841", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#41d5d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#d8c241", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#416cd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#d89e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#d88141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#d8415e", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d84187", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#41d89b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41bed8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#bad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#4177d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d87d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41b2d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#a8d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#d88141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#417dd8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d86a41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#4189d8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#41cad8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#d88141", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#9d41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#6ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#4177d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41b8d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#416cd8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d89941", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41b2d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#6ed841", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#419bd8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#4189d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#4177d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#4166d8", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d841aa", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d877", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#41d88f", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#a2d841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41d8ac", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#8bd841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#7fd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#41bed8", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#4166d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#41bed8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#4189d8", "style": "normal"}, {"source": "t_esc_serial_passthru", "target": "m_voxl_esc", "color": "#4148d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#41d89b", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#7941d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#bad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#4177d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#41d87d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#7fd841", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#4177d8", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d87541", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#8541d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#41cfd8", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#6241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4195d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#416cd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#4177d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#4166d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#4ad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#41bed8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#41d8b2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#62d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#41a0d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#41d8be", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#d141d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#d841cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#7fd841", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#41c4d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#41d848", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d87b41", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84641", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d88f", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4ad841", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d84199", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#4189d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41cfd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841c8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#ba41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#4177d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#79d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#73d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#68d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#7fd841", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#4142d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#9d41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d8b2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d8ca", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#7fd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841c8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#ba41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d87b41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#4177d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d84193", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4195d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84181", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#b4d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#5cd841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41a6d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#4177d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#4171d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#416cd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#41bed8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#41d8b2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#62d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#41a0d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#d141d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#d841cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#7fd841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#41d848", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d87b41", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#9d41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d85841", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#41d85a", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#41d842", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#41d842", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#7941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8419e", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#41d842", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#41bed8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#8b41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8419e", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#41d842", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d842", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#9d41d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d89e41", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#6ed841", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d84158", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#ccd841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#4189d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#7fd841", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d841c2", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d871", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#4177d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#73d841", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d8b8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#4189d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d8418d", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#416cd8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#68d841", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#6ed841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d84c41", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d141d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4195d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#5cd841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d86441", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#50d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#4189d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d88141", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d841b0", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d84e", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#416cd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41bed8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d88d41", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d89341", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8aa41", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d84193", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#4441d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d8417b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d877", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d8c841", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d8d341", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d88f", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#6e41d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#8541d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#9dd841", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#a241d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d8b8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d8ca", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#85d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d8cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#7fd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41cfd8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8414c", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#79d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#7941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d8ca", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d841c8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#4183d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#4177d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#5041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d877", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#4177d8", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d84e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#9d41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41a6d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#4177d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#4171d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#416cd8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#5641d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#cc41d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d8b041", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d741d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d841d3", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d8bc41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84181", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#4177d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84641", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4195d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d8ca", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#85d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d86441", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d84193", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841c8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d87b41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d841b0", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41a6d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#44d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#9d41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#5cd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#4189d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#4177d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#9141d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#4177d8", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#d8bc41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#56d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#41d88f", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4ad841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#7fd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41cfd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#8541d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#73d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84641", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d84c41", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d85e41", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d85241", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d85841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d86441", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d88141", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d88741", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d88d41", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d89341", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d89e41", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d8a441", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#d8bc41", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#d8cd41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d7d841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#aed841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#85d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#7fd841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#73d841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#68d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#5cd841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#50d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#41d842", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41d854", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#41d85a", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41d860", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d877", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d889", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d88f", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d895", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d8b8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d8ca", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d8cf", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41cfd8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41b8d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41a6d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#4189d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#415ad8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#4154d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#414ed8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#4a41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#5641d8", "style": "normal"}, {"source": "t_obstacle_distance_fused", "target": "m_mavlink", "color": "#5c41d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#7341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#8541d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#8b41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#9141d8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#9741d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#a841d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#ae41d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#c041d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d841bc", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d8419e", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d841a4", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d8418d", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d84170", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_internal_combustion_engine_status", "target": "m_mavlink", "color": "#d84164", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84146", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#7941d8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#9d41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#91d841", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d866", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#4189d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#4189d8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d8a0", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#416cd8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d84e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8a6", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84146", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#415ad8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d84c41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41d88f", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#7fd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#ba41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#4177d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d88d41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4195d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#41d8cf", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d86441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#4189d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d84193", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#5641d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#6841d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41b8d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#41bed8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#41d8b2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#62d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#41a0d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#d141d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#d841cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#7fd841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#41d848", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d87b41", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#56d841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4ad841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d86441", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_full_no_mavlink.json b/docs/public/middleware/graph_full_no_mavlink.json index c0ff7fa2ff..2164f67cc1 100644 --- a/docs/public/middleware/graph_full_no_mavlink.json +++ b/docs/public/middleware/graph_full_no_mavlink.json @@ -1 +1 @@ -{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d8418d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8ac41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#92d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84176", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d85041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d86741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d85f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#d89541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#41d890", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#4190d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#8341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#d841b3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d841ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#a1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#4169d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#c8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d84167", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d869", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#46d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#41d897", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d8cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#64d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#4197d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#4641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#4d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d8d241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#74d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#4dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#4162d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#9241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d84150", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d87641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#b8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41cdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41c5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#6c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d88d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#7441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#83d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#6cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d862", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#6441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#b841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#c841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d8415f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#a141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d8c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d8d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d84195", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d8b341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d84150", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#a141d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#d841a4", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#b141d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#b841d8", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#7bd841", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#41d852", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#7441d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d841ca", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#b141d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#b841d8", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#d8b341", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#d8b341", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#7441d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#6c41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#c0d841", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#41d8bd", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d8415f", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41d8a7", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d8415f", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#7441d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#6c41d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#d84148", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#d841bb", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d8c341", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d8c341", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d8c341", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d8c341", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d8c341", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#d8416e", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#b841d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#9a41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#a141d8", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#d8b341", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#b141d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#41d890", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#d89541", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#41aed8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#8341d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#41d89f", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#d741d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#d85741", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#41bdd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#55d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d8416e", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#8a41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#9a41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d84148", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#9ad841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#a941d8", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d8d4", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d871", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d85a", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#4169d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d85a", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#a1d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#5dd841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#a1d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d8cd", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#a1d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d87641", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#41d890", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#d89541", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#41aed8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#8341d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#41d89f", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#d85741", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#41d8a7", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d841c3", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#4152d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8ac41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841d2", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d88541", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d84167", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#b841d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#d85041", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#64d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d841d2", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#d841bb", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d841ac", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#d88541", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#41d888", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d8ac41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d8c341", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#d8d241", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#c841d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#6cd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d841d2", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#4188d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d841ac", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#41d879", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#d88541", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#4143d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#d8a441", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d8ac41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d8c341", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d8b341", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#4641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#c0d841", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#b841d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#41a7d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#83d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#4197d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#41d852", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#4179d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#4169d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#4162d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d84195", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d8418d", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d8417e", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d84150", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d7d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#a9d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#a941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41c5d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#8ad841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#5541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#5d41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d88d41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d7d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#cfd841", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d87e41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d8bb41", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#46d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d84b", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#415ad8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d869", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d84b", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d7d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#4190d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d4d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#b1d841", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d86741", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d741d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d86741", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d85f41", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#a1d841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84176", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#c8d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#4dd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41d843", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#4152d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#414bd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d84185", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#7b41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#cf41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d8416e", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d8ca41", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d85f41", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d85f41", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#4d41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#41d84b", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#41d8cd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#c041d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d87641", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#41b6d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#d741d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#d841b3", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#92d841", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#d86e41", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d8c5", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#9a41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#55d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#a941d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#41d888", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#74d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#419fd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8b6", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d8cd", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d87641", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d880", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d86741", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d85f41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41d8ae", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#41d897", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d862", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d84157", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#9241d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d8419c", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#415ad8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d869", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#b8d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d86741", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#92d841", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#b1d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#41d890", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#d89541", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#41aed8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#8341d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#41d89f", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#d85741", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d84148", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d7d841", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#4641d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#6cd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#55d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#d8419c", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#d8a441", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#4d41d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#64d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d84148", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41cdd8", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d8415f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#d86e41", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#d841a4", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#9241d8", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#41d862", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#d86e41", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#5541d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#b141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d84148", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d7d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#a941d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#4152d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#c841d8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d89c41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#41cdd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#41d852", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#b841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#d7d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#4169d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d88d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d7d841", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#4190d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#cfd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#d86e41", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d841ca", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#b141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#cfd841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#b841d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#d88d41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#cfd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#5541d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#cfd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#d7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#d7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#9241d8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#41d8bd", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#b841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d7d841", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d89c41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#41d897", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d8a441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d84148", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#a941d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d7d841", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d8415f", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#74d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#55d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d84b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#4190d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#4169d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d862", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d88d41", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d89c41", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d7d841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d8d4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#d88d41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#d7d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d8bb41", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#41d862", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#d86e41", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#55d841", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d7d841", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d8418d", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#a141d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#d8d241", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#d84148", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#d841bb", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4143d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#d86e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d7d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d7d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d862", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d862", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#41d862", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d862", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#41d862", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d862", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#414bd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#4190d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#d89541", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#41d890", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#55d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#41aed8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#8341d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#d85741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d8bb41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#a9d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#41d869", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#4dd841", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#4152d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d7d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d8d241", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d8416e", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#cf41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#41d897", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#9241d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#d841b3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d841ac", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d871", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d841c3", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#9241d8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d84148", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d7d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d84185", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d869", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#41d897", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#a9d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#b8d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#d841b3", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d85f41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d8bb41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#55d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#6cd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d7d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d84157", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#4190d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84176", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#4190d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#41d897", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#41d85a", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#4169d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#41d85a", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#4190d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#41d897", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#a1d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41cdd8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41d843", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#4190d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#41d890", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#d89541", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#41aed8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#8341d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#d85741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d8bb41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#a9d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#55d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#41d888", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#6c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841d2", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d84167", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#64d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#9241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d7d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d8d4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#4190d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#74d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#9241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8ac41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d841d2", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#d88d41", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d8d4", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#74d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#4190d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#9241d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#419fd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#5dd841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#9241d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#64d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d84167", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8ac41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841d2", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d7d841", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41b6d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#41d852", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d89c41", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#9241d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d741d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#4169d8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#4162d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#55d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d871", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#4d41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#a941d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d7d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#9241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41cdd8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#41bdd8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#b841d8", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#7bd841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41a7d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#6cd841", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#4197d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#55d841", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#46d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#4190d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4180d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#4169d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d8419c", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d84185", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d89c41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#41d897", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4143d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d8417e", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41d8a7", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d8416e", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8b6", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d8ca41", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d8c5", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d84157", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#5d41d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d8d241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d7d841", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#7441d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#cfd841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d4d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#9241d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#8a41d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#a141d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#9a41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d84148", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#b1d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#9ad841", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41c5d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d7d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d8416e", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#4641d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#6cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#9241d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#b8d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#55d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#b1d841", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d4d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#4190d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#a9d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#a1d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41cdd8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41d843", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#8ad841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d8cd", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d7d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d87641", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d85f41", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d8b341", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d8bb41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#b1d841", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d84157", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d84185", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#7b41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41a7d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4143d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#6cd841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#cf41d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d8c341", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d8bb41", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#9ad841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d8416e", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d8415f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#a1d841", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#4190d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d869", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#41d897", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#a9d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#a941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#4190d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#4180d8", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#d8b341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#d7d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#d8d241", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#4188d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#55d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d871", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d7d841", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d8415f", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#83d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#41d888", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#4190d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#a9d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d85041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d7d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#9241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#4169d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d89c41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#41d897", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d7d841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d4d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d84148", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#a9d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#92d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#41bdd8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d7d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#4152d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#c041d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#9a41d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d85f41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d84148", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#d841b3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#55d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4143d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#41a7d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#6cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#9241d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#415ad8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#4169d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#55d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d8a441", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#b1d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#4190d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#d89541", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#41d890", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#41aed8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#8341d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#d85741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d8bb41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#a9d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#55d841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#4188d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d7d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#41a7d8", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#92d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#4dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d897", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#41d8cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d841d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#4d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8d241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#74d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#64d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41c5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#4162d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#6c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84167", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d8b341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#a141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#6cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d890", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d841b3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d84176", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d8415f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d84195", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d8418d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d85f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#41d862", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#4169d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#8341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d85041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d8ac41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#b8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#83d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#7441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#b841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d841ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84150", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#c8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#4197d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#4641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#46d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#6441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#d87641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#c841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#d86741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#41d869", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41d8c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d8d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#41cdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d89541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d88d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#4190d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#9241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#a1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#4188d8", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d89541", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#d86741", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d7d841", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#d85741", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#46d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#c8d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d7d841", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#c8d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d85041", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#4641d8", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#d87641", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#41d869", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41aed8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#41d869", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#c8d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d85041", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#41d85a", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#d88541", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#41d8ae", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#9ad841", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#d89541", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#d7d841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#64d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#d8c341", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#41d888", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#74d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#d841d2", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#d841ca", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d8ae", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#cfd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#a9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#a1d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#41bdd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#c041d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#9ad841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d88541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#9241d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#4143d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d84141", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#9a41d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41b6d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#b841d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#64d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#d8c341", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#41d888", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#74d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#d841ca", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#41aed8", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d841b3", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#4190d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#4dd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#4180d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d84185", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d84148", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#41a7d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d86e41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#4dd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#4180d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d84185", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#41d85a", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#4d41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41a7d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#4dd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#4180d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d84185", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#4641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d8b341", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d84141", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d85741", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d85f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#cf41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d87e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d841ac", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#4188d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d8418d", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8417e", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41d84b", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d8415f", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#5d41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84150", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d8bb41", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#7b41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d89f", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d87e41", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d84157", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d8a441", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84150", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#41d843", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d871", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#6cd841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#4171d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41c5d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8d241", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84150", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#4171d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#b8d841", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d841d2", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#41d8cd", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d741d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#4179d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d4d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#41d862", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d8ae", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#4190d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#b1d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#a941d8", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#5541d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#b841d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#4162d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#415ad8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d880", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#41b6d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#d841d2", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#4171d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#b141d8", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#92d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d879", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#41bdd8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#9ad841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d86e41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4152d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d897", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#4197d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#419fd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#b841d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d84176", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41b6d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#41d8a7", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#55d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d871", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#6cd841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d8ac41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8d241", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#64d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#d8c341", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#41d888", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#74d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#d841ca", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d88541", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d84150", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#41bdd8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#41d843", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#41d890", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#5541d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#d88d41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d8ca41", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d88541", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d8419c", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#4152d8", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#5dd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#d8419c", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#9a41d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#83d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#7441d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#4190d8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d87e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#7441d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#41d8c5", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#41d8d4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#d84150", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#d85741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#92d841", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#46d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d84150", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#83d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#41d8d4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#41d8b6", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#83d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#83d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#415ad8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#d87641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#41d8d4", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d89c41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#41d8a7", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d84150", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d88d41", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#41bdd8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d8ca41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d7d841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#9241d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d84841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#9a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#41bdd8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#83d841", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d87e41", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#5dd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#4171d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d8419c", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4152d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#d8ca41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#415ad8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#41d89f", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#5dd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#d84150", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#d8419c", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#d87641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#41bdd8", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84150", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#d89541", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#41d85a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#d88541", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#8341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d88541", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d84150", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#5dd841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#41d862", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#64d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#d8c341", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#4169d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#41bdd8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#d88541", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#74d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d8ca41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#4162d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#41d862", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#8341d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#4190d8", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d841b3", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#4143d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#41d8a7", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#b1d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#41bdd8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#4641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d4d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41d84b", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#4162d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d89c41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#41d8a7", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#83d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d8ac41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#6c41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#55d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84150", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#c841d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841a4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d852", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d89f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84150", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#4179d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#7441d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#64d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#d8c341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#41bdd8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#d88541", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#74d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d88541", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d85041", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d84185", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d84148", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#d8ca41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d8419c", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#41d897", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#d8ca41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#7441d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d8ca41", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d89c41", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#a1d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d85741", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d87e41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d85f41", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#41bdd8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d84141", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d841d2", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d8bb41", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#b141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d8ca41", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84150", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#41d843", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#7441d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d8ca41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#8341d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8d241", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#41d8a7", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#cfd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d8ae", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#c8d841", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#b8d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#a141d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41d8c5", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#a9d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d8d4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41c5d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#41bdd8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#c041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#8ad841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#9ad841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#cf41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#83d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#7bd841", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41aed8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#4197d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d87e41", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#55d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d88541", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d8419c", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d8418d", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d89541", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d84176", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d89c41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d8415f", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d879", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#6441d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d8a441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d890", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#415ad8", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d4d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#d841bb", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#41bdd8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d8ac41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841a4", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#b8d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8d241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d88541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d89c41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d841a4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d852", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#7441d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#419fd8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#b841d8", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d89f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8d241", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d84157", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41b6d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#6c41d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#a9d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d4d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#55d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#8ad841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#b1d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d841c3", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d852", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d841a4", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#4188d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#d89c41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d84150", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#d8416e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#41d862", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#8341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#41bdd8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#4143d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#83d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d8b341", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#41a7d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84150", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#41d869", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d89c41", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#4d41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d8bd", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#b8d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#4162d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#415ad8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#41bdd8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#c041d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#9ad841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#6c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#8ad841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#6441d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#7bd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#6cd841", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d88d41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8d241", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#64d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#d8c341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#41bdd8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#d88541", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#74d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#41d84b", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#41d862", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d8b341", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84150", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#8ad841", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v2.json b/docs/public/middleware/graph_px4_fmu-v2.json index b1d931e96e..202abfcb01 100644 --- a/docs/public/middleware/graph_px4_fmu-v2.json +++ b/docs/public/middleware/graph_px4_fmu-v2.json @@ -1 +1 @@ -{"nodes": [{"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d84b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d86041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41c9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#9fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#4b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d84160", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d8419f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d8414b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#9f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#4bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d89f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d8c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_board_adc", "target": "t_adc_report", "color": "#d88a41", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#4194d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#9f41d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#41d86a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#414bd8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#b441d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d86a", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#414bd8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#b441d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#d8416a", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#4141d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#d8416a", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#4141d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#b4d841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#b4d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d8a941", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#418ad8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41d84b", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#416ad8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d8419f", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d341d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d8c9", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d8a941", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#7541d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#418ad8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41d84b", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#416ad8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#bed841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d8417f", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d341d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d84155", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d8419f", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d8418a", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d8d341", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d8a941", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d8d3", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#7541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#418ad8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#9441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#a941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d8414b", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d84160", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#75d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d85541", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d86041", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#417fd8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#416ad8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d84194", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d894", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#8a41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#7541d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d84b41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d841d3", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841a9", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d87541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41a9d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#419fd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d8be41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#7f41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#6041d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#4b41d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#4175d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#a9d841", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d8b441", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#7541d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d8419f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8c941", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#6041d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41c9d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#75d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d8a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#5541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#7541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#9f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#be41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#b4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d8be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d8c9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#9fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#94d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#8ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41d3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#41bed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d841be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8416a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d841b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#41b4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d87541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d8419f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d87f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#4bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#60d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d89441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d855", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41d86a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d87f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d84155", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d88a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d8be41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d89f41", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#9fd841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#55d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d875", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d89441", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#4b41d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#9fd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#d84141", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#7541d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#9441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d89f", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#c941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#8ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#7fd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#75d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#6ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d841b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d8419f", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#4175d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d860", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#4155d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d84175", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d8be41", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8c941", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d3d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#c9d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d841c9", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d89f41", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#4160d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841a9", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#41d8b4", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d341d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d88a41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d8a941", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#414bd8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#414bd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d8419f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#6041d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d8a941", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#418ad8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#417fd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41c9d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#416ad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d8419f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#6041d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d8a941", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#418ad8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#417fd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41c9d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#bed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#75d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#416ad8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#75d841", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d88a41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8c941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d3d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#9f41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#9441d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d84b41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d89f", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#41d8b4", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#b4d841", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d8be", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#a9d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d841d3", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41c9d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d8419f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841a9", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41a9d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#419fd8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#4175d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d8417f", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#416ad8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#4160d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d86a", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d860", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d8a941", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#4155d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4141d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d8be41", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8416a", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d84160", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d84155", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8c941", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d8d3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#75d841", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d8419f", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#60d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d87f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41d3d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841a9", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#75d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d89f41", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d8419f", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d87541", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#55d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d8a941", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#75d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#4160d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d8419f", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#6a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41c9d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#75d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#75d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8c941", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d8a9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41c9d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d84b41", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d89441", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d89f41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d8c941", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d8d341", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d3d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#c9d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#b4d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#9fd841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#94d841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#4bd841", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41d86a", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d860", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d87f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d89f", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d8c9", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#41bed8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41c9d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#41b4d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#419fd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#9f41d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d841be", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d8419f", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d84194", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d84155", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d8414b", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#a941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41c9d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d87541", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#4b41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#9fd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41c9d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d86041", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#75d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d8419f", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#c941d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d84194", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d84175", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d87f", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d8be41", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#4175d8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d87541", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#be41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8c941", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d8c9", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#5541d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#b4d841", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d88a41", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#419fd8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d3d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#a941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8416a", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4141d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#4160d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841a9", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d89f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d86041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d8c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#9f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d84b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d8414b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d8419f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d84160", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#9fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#4b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41c9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#4bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_board_adc", "target": "t_adc_report", "color": "#d841b4", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#5541d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d87f", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#d8416a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d894", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d87f41", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d894", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#d8416a", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d87f41", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#d841be", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#d841be", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#41d875", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#41d875", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#be41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41d860", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41bed8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#be41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41d860", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#9fd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#75d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41bed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d8c941", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#be41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d87541", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d89f41", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41bed8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#60d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8be41", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#a941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#9441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d84160", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#4b41d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d86041", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41d860", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d86a41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d84b41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841c9", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d3d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d8a9", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#41d8be", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d8417f", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d8414b", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#c9d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#8ad841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#416ad8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d8c9", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41c9d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#8a41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#8ad841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8be41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41a9d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d8419f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#94d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#4bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d84b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d85541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#418ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#417fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d87f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d8a941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#4160d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#4155d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#c9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d841be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#bed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#a9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#41d875", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d87f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d88a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d841a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#6041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#41d8b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#41d8be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d84194", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#75d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#60d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d84155", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d841a9", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d855", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d89441", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#416ad8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#c9d841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d841a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#9f41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#4194d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d85541", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#418ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#b441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8be41", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#b4d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#4141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#41d8b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d8c9", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#9441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#55d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41a9d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#c941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#7f41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84175", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#4bd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841c9", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d89f", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#6a41d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d841b4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#be41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d894", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d894", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#7fd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41d860", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#8ad841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#94d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41d860", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#8ad841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d8be41", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d8c941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#94d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d8d3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8be41", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d841b4", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#9f41d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d84b", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#be41d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41d860", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8be41", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841c9", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d3d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d841be", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#4141d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#b4d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41d875", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d87f", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#9fd841", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d89f", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d8419f", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d8c9", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#6a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d3d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d84194", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#8a41d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d8417f", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#6ad841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41a9d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#419fd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d8414b", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d86a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41a9d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d87541", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d85541", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#7f41d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84175", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#4bd841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d88a", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8be41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#a9d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#4175d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d8418a", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8be41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d89f", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#c9d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d87541", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d841d3", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8be41", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d8419f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41a9d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#94d841", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d84b41", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d89f41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8be41", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d341", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#bed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#94d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#55d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#4bd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d87f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d88a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d89f", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d3d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41c9d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#419fd8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#418ad8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#417fd8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#4175d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#4141d8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#4b41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#9441d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#9f41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#be41d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d84160", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d8414b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d87541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#416ad8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d8c9", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d87541", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#6ad841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d86041", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d87541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d8418a", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#41d8be", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d88a", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d8b441", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#418ad8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41b4d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d86a41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#b441d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d8c9", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41a9d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#75d841", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#6041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41d875", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84175", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d8417f", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841c9", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d84155", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d87541", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#6a41d8", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v4.json b/docs/public/middleware/graph_px4_fmu-v4.json index f4a5be44af..3c4197a667 100644 --- a/docs/public/middleware/graph_px4_fmu-v4.json +++ b/docs/public/middleware/graph_px4_fmu-v4.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#82d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#82d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#416cd8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#4143d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#4143d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#53d841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#53d841", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#53d841", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#41d850", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#a441d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#abd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#41d880", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d87741", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#5341d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#41d8af", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#41d85e", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d8af", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41d85e", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#5341d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#9741d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#c6d841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#41d8af", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#d4d841", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#97d841", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#97d841", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#97d841", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#97d841", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#97d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#a441d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#abd841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#41d880", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d87741", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d8a641", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#a441d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#abd841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41d880", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d87741", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#c641d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#b941d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#41d850", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#41d850", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#ab41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#a441d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#b941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#abd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#c641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#41d880", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d87741", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d841ad", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d84170", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d87041", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#419bd8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#7bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d87741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#a441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d85541", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#414ad8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#b941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41a9d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#b2d841", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d84177", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84147", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d841cf", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d84199", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41d880", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8a041", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#41d8a2", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#9741d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#41d8d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#cd41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d86c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84184", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#c6d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#6741d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d84170", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d84169", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#9041d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#b941d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d8cf41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#4172d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#bf41d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#67d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#41d84a", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#418ed8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#6ed841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#d8cf41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#7541d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#41d879", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4cd841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#d84192", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#7541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#d8c841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41d8d1", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d8415c", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d86941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#4541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#5941d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d8414e", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d89241", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#d8417e", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#4165d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#9741d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#cd41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#9041d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#6741d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d8ad41", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41d872", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d8cf41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d8cb", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84147", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d87e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#90d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#89d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41bdd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#75d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#b241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#59d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41a9d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#53d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#45d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41a2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d841d6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#d88441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#4194d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d89941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41d857", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d841a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41d887", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#415ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#d8417e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d8a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#a4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#5341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#6741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41d8af", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#41d8b6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#97d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d84170", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d8414e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#9041d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#67d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d86241", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#4172d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4cd841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#8941d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#90d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d1d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#89d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41b6d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d843", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d88b41", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d841bb", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d89241", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d841b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d841a6", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#cdd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#4c41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d84177", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#9dd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#6741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84147", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d87e41", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d441d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d84741", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d841c8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#c6d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#b9d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84155", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#53d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d8bb41", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41a2d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#a441d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#8241d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#abd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#41d880", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d87741", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d841a0", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#41d8af", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#4157d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d841c2", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#4187d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#41d8bd", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d84e41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d84162", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d8b441", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#6e41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41a2d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#b941d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#bfd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d441d8", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41afd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#9d41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#7541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#6041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d441d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#a441d8", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#b941d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#41d8af", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41afd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41afd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84147", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d841bb", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d8418b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#d8c841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#d8cf41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41afd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d87741", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#5341d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#5341d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#d84e41", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#b941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#b941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#b941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#b941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d8418b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#d8c841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#d8cf41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#41afd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d87741", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d8418b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#d8c841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d8cf41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41afd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d87741", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d84170", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41afd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d84170", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#41d8c4", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#6741d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#41d850", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#41d8c4", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d84177", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#41a2d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d89b", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41afd8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#b941d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d87741", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#d88441", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d89241", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41d857", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#41d880", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41d887", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d8418b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#d8c841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#d8cf41", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#41d89b", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#5341d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#9041d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#9741d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d89241", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#4150d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84147", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#9041d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41a2d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d84170", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#9041d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84147", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#82d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d8414e", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#6741d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#9741d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#41d8d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d84e41", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d85541", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41b6d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41afd8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41a9d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#53d841", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#c641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d87741", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d87e41", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d88b41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d89241", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#4187d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41d850", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d865", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d86c", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d8a641", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d8ad41", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d841a0", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#416cd8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#4165d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d8418b", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84184", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#4157d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d8d641", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#b9d841", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#4c41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d84177", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#6741d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d84170", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41d8c4", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d8cb", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d84169", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#419bd8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#4150d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#414ad8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#7541d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d441d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d87e41", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#89d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#75d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d89241", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#6e41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41afd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d879", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41a2d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#6ed841", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84147", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#7bd841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41afd8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41afd8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d88e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d84170", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#67d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#d8418b", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#414ad8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#d841ad", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#41afd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#9041d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#6741d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#414ad8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d85c41", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8a041", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d8418b", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d89241", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41bdd8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41afd8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d8414e", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#6741d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#4187d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#bfd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#4150d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d841ad", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#414ad8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#b9d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d86241", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#9dd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d84170", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#75d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#d84170", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#41afd8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#9041d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#d87741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d8418b", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#4194d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41afd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84147", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d8418b", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d87e41", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d85c41", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d88b41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#b9d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#a4d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#9dd841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#90d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#7bd841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41d85e", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d88e", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#41d8a2", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41d8d1", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41bdd8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41afd8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41a2d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#418ed8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#415ed8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#4150d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#414ad8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#4143d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#4541d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#5341d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#9041d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#9741d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#ab41d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#cd41d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#d841c2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d841a6", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d841a0", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d84192", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d8418b", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84184", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#d8417e", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d84170", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d84162", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84155", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d8414e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d84170", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#67d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8418b", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#414ad8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#9041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#414ad8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41d8c4", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d85c41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84147", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#90d841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84184", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d89241", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#d8417e", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d841b4", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#60d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41afd8", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d841a6", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#41d8a2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#9041d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84147", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#6741d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#41d8b6", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#7b41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d87e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#414ad8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#9041d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#6741d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#41d8d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#82d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#97d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#4157d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#4187d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#b9d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#c6d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84155", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#53d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d8418b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#d8c841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d8cf41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41afd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#8241d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#abd841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#4157d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#4187d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41afd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d841a0", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d85c41", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#414ad8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41afd8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#4cd841", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#45d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d89241", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84147", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d84177", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d84170", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#9041d8", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#d84147", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#6741d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d84147", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#41c4d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#41c4d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#4194d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4194d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#53d841", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d89b", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d841c8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#419bd8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d4d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d4d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41d8d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#59d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d841cf", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d88e", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d8cf41", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8a641", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d8414e", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41d8cb", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d8d1", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d1d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#4187d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d85c41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#9741d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#9dd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#b941d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#75d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#53d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d86241", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d841b4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d87741", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#4157d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d8c241", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d88e", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41a9d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d441d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#a441d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88b41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#41afd8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#41a9d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#41d85e", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#d84e41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#8241d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#c641d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#b9d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#4541d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#9041d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#4541d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d85e", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4179d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#4165d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#4cd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#7541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d85541", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#4143d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d84169", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d87041", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#d84192", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#ab41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d84141", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#4157d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#a4d841", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#bfd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8a641", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41a9d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d8b6", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#b241d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d8b441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#89d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#cd41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#41b6d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d87e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#418ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d841a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#d89241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#d84192", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d857", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8a041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d84177", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d84170", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#414ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d8bb41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#5941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#5341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#4c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8c841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#41d879", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#7541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#b2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d89b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8a2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#9741d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88b41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d841c2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d441d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d86941", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#90d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#89d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#7bd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41bdd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d87041", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#4187d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d841a6", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d88441", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d850", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#416cd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8a641", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d872", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d84162", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#8941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8a2", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#b241d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41afd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4172d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841ad", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d8417e", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d84170", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#53d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#45d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#41d887", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d8c4", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d84170", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#abd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#41d8a9", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#6ed841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#6041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d85e", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#67d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#4541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#cdd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d8a641", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#7bd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#41d84a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d89941", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d89941", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4150d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#4180d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#4180d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#4180d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#4180d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d8a641", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#9041d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d88e", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d88e", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#7b41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d84199", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#c6d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d84170", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#4187d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#a441d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#9dd841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d87041", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41a9d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#418ed8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#4187d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#41d84a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d89941", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d8a641", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d8ad41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d8b441", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#4c41d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d8d641", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#cdd841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d87041", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d841bb", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#bf41d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d88e", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d84170", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#9041d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8a641", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#9041d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#7b41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d88e", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#41c4d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#97d841", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d8b6", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#ab41d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d8bd", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#82d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#6ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#53d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d86241", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d841cf", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#41a2d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d87041", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d841bb", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d841b4", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d87741", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41d843", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#4187d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d84199", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d850", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d857", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8a641", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d8417e", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4150d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d8b441", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d865", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8c841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d872", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#6741d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#6e41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d8415c", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d88e", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#9741d8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#a4d841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8a641", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d85e", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d1d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#67d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#4541d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d85c41", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8a2", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#d84192", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d841cf", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d87041", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841ad", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#cdd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#c641d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#5341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d8a641", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#c6d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#9041d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8a641", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d8414e", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#cdd841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d1d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d87041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8a641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#d87041", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d84199", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d87041", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#b941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41bdd8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#7b41d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d88e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d8b441", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8a641", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41d843", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#6ed841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8a641", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d8bd", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#bf41d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d1d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#53d841", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d89b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#d84192", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d87041", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#5341d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d8b441", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#5941d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8a641", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d8b6", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88b41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8a641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d8cf41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#cdd841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#97d841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#59d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#41d879", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d88e", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d8d1", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41bdd8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41afd8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#41a2d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#419bd8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#4143d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#8941d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#8241d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#9741d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#ab41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d841b4", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d841a6", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d84199", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d8418b", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d84177", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d84170", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d84169", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d87041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88b41", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84155", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d87041", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d87041", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#b941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84141", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41afd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d87041", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#90d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#89d841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#cdd841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#75d841", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#b9d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#4187d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d841a6", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d88441", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#419bd8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#cd41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d8418b", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#7b41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#41a2d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d8bd", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#82d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41d843", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#6ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d841a0", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d8a9", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d841d6", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#cdd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#82d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#60d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d87041", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8a641", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d84184", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#cdd841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d88e", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v5.json b/docs/public/middleware/graph_px4_fmu-v5.json index aab845cf57..3177688f80 100644 --- a/docs/public/middleware/graph_px4_fmu-v5.json +++ b/docs/public/middleware/graph_px4_fmu-v5.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#6bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#41d8d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#a7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d8416f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#57d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#41d8b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#6b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d841d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d8b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#5ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d8419e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d87d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d89841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41d8a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d841c0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#bbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#72d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#4174d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#8641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84191", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d84183", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d89141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d89c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d86f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#c241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d8c041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#a0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#6441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#bb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d8ac41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#41d874", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#78d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#419cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#a041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d841cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d8a541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#64d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d86d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#4181d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41d881", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#4195d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#416dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8417d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#b5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d895", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41a3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#417bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#5e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d841c6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d84198", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d87641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d88341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d8cd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41d84c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#41d87b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41b7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#7241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d89e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#414cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d841b9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d8c641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#86d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d8b941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8d441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#c2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41b0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#b541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#5741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d841a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#7841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#a741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84176", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#41d8a9", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#41d8a9", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d8b241", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d88341", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d88341", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#93d841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#93d841", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#93d841", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#41d888", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#41a3d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#41cbd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#50d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#5741d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4159d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d88a41", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#4181d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d852", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#41d874", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#41d874", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#41d874", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#41d874", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#41d874", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#41d888", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#41a3d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#50d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d841a5", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41d888", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41a3d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#50d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d84141", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41d888", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d841b9", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41a3d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#50d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#c2d841", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#d84141", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#d84141", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#d84141", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#d84141", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d84141", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d841b9", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#c2d841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#41cbd8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#41d866", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#4160d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#41d888", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d841b9", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#41a3d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#41cbd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#50d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#c2d841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#a041d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d88f", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#41d87b", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d89e41", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#c2d841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d84169", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#72d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#6b41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#7241d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#50d841", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#aed841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d860", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#41bdd8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#a0d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#6441d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41a3d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d641d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8417d", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d84741", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#416dd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d86f41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d841c0", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d89141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41d881", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d84183", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d88f", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d89c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84176", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#c2d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d8ac41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#86d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#4145d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#8cd841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#4941d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#4174d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#d86941", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#86d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#d8b941", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d8cd41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#4188d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#a7d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d84147", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4341d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#4188d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d8cd41", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#8cd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d86d", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d895", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#64d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#41d845", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#4152d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#5ed841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d8419e", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#7fd841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8cb", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#7841d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41b0d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d841b2", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#86d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d87641", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#ae41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d859", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#41bdd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#93d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#8cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#9a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#a741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#c241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#cf41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#417bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d841cd", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d86241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#43d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#41d845", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d87d41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d852", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#414cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d88a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d89141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#4145d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d89841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#41d874", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#5741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d8c041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d84183", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8d441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d88f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#41d8b7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d8b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#41d8c4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8cb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#8641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d84169", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#bbd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8415b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#b5d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d84155", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#9ad841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#8cd841", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d89841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41b7d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d8ac41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4341d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#4145d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#8cd841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#c941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#7fd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#a741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#6bd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#41a9d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#4195d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d841cd", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#49d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d841c6", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d89e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d8a541", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#5e41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d84183", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41d8a3", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#c9d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#41bdd8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#ae41d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d89841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84162", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84191", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#93d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d86241", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d84741", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#78d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841ac", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#419cd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d6d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#41d888", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#41a3d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#bb41d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#50d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#b541d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#5741d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#4166d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d86241", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d84198", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#9341d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d8418a", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#41d8d2", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d8c641", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#418fd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d841d4", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d85b41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#c2d841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84162", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84191", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d89841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#cfd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d89841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#7f41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84191", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d84e41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84162", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d85541", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d8cd41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#4188d8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#c2d841", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#8c41d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d89141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#50d841", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#6bd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#41bdd8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#86d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#4941d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d895", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#6441d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#41a3d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#50d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d8414e", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d88a41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#d8c641", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#c2d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#c2d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#c2d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#c2d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#c2d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#41bdd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d89141", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d84141", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d89e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d84183", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d89141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#86d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#4941d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#41d895", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#6441d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#41a3d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#50d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#41bdd8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d84147", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#86d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#4941d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d895", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#6441d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41a3d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#50d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d8414e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#86d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#4941d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d895", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41a3d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#cfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d859", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#50d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d8414e", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#41bdd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#41bdd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#41bdd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#cfd841", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#41d8a9", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#50d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d84183", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d89141", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d86241", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d89e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#41d84c", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#41cbd8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#7fd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#86d841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#41a3d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#50d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d859", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d88a41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d89141", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d89e41", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#4941d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d8c041", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#cfd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d895", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#c2d841", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#bbd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#8c41d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d84155", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#41bdd8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#4174d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#7fd841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84191", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d8b941", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d841c0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d89141", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#8641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d88f", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d6d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#41bdd8", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#41d8a9", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d84183", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d88f", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d88341", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#93d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#7fd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#78d841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d84e41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#a041d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#ae41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#b541d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41a3d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#419cd8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#c241d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#4195d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#50d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#49d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#4166d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d86f41", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d87641", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d841b9", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d841c0", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d841b2", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41d84c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d859", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d841a5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d89141", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d84198", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d8b241", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d89e41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d8a541", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#5741d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41d881", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d8c641", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d84183", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#5e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#cfd841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d89c", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#7841d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84176", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d84169", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d2d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84162", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#72d841", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d85541", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#ae41d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d8cd41", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#4188d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#a0d841", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d86241", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#4174d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d84198", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8cb", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#8641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#7fd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841ac", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#419cd8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d6d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#41bdd8", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#41bdd8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d84147", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#7841d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41d84c", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#7241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d89841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41b7d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#a0d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d89841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#a0d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#d84183", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#d84176", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#cfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#a0d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#a041d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41d84c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#a0d841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#7fd841", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#43d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d84183", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#41a9d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d87d41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#cfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41d8a3", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d8b0", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d85b41", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#41bdd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d8c641", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#4174d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#78d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84191", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41b7d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d84183", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#50d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#a0d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#4145d8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d852", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#41bdd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41d84c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#cfd841", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#417bd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#41bdd8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#4166d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d859", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d87641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#ae41d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d86241", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d86f41", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d87d41", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d88341", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d89841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d89e41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d8a541", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d8b941", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8d441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#cfd841", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#a0d841", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#9ad841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#93d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#7fd841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#64d841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#5ed841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#50d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#49d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#41d84c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d859", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d860", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d86d", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#41d87b", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41d881", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d88f", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41d8a3", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#41d8d2", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#41bdd8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41b0d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#418fd8", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#4181d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#416dd8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4159d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#4152d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#414cd8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#4341d8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#5741d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#5e41d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#6b41d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#7241d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#7841d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#9341d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#a041d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#a741d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#ae41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#b541d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d841d4", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d841cd", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d841c0", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841ac", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d8419e", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d84198", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d84183", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8417d", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84176", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d8416f", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d84169", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8415b", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d89841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#a0d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#c941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d8ac41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#a0d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41d84c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d859", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#a0d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d841cd", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d89141", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d89e41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#7fd841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8cb", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d841c6", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#a741d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d84183", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#cfd841", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#c9d841", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#a7d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#41bdd8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84176", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d84141", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#cf41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#ae41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d89841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d84183", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#a0d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d89141", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#4145d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#93d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#41d874", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#78d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8418a", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d84741", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d86f41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d8c641", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841ac", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d85b41", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#a0d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#86d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#4941d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d895", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#6441d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#41a3d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#50d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#cfd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#41d8d2", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#41d8d2", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d8d2", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841d4", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#41d888", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#bb41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#4166d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d8418a", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d8c641", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d89841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#a0d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d89141", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#a0d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#a041d8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d87641", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d89141", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#4341d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d89e41", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d8b941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#cfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8b7", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#a0d841", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#b5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#8641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d8ac41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84176", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d87b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#4181d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d895", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#4174d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#a741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d841ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#419cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d8c641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#5741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d8a541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#57d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41d881", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d841b9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41d8b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41a3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8d441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#414cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d84191", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#d88341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d89e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#c241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#bbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#41d86d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41d2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#6b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41b0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d841cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d8417d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d8cd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41b7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#b541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#d87d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#5ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d89c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41d8b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4195d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41d84c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#41d8d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d841d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8419e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d84198", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d89141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d8b941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#a0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#86d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d841c0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#a7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#64d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#5e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#6441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#a041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d89841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#72d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#6bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#417bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#78d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#bb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d8416f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d86f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d87641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#c2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d84183", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8c041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#416dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d841c6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#7841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d874", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d841a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#7241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#c9d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d8414e", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#c9d841", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d84169", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d84169", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4145d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#5e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d841b2", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#d87d41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#4341d8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#41d845", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#72d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#78d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#72d841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#d88341", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#8c41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#72d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#b541d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41cbd8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#a041d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d84e41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#7241d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d88a41", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#bbd841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d86941", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d89841", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d8418a", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d841ac", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#6bd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41d2d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41d8b7", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d84198", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d866", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d89e41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d8b241", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8419e", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d8c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#7f41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84162", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41cbd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#9341d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#4159d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d8417d", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d8416f", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41b7d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4181d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d895", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#41d8cb", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#bb41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#d8416f", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#d841cd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d84191", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#d8ac41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d8cb", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#5ed841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d89c", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#ae41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d8c641", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#86d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#5741d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#4174d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d859", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41b0d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d874", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#417bd8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#c2d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#64d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8d441", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d8416f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d86941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41b0d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#50d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#49d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#c241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#41a9d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#419cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41d852", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d860", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d87641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d8a541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d841b9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#4174d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d87b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8c041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d841b2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d8b941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d841a5", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#4152d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#4341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4145d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d8417d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#6b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#41d8d2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#a0d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#7241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#7841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84162", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#d8415b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#9341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41bdd8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4181d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d895", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#a7d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#4159d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d8417d", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#cfd841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#49d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#c941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#cf41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d86941", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4195d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d859", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d841d4", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#416dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41d881", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d841a5", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d6d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8a3", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#8641d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#9341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#6bd841", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8d441", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#414cd8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d8cd41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#7841d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d866", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d841c0", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#93d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84155", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#41d86d", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4145d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#a741d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#7841d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#4188d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#b5d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84176", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41d8b0", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#414cd8", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d8cb", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d8d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#414cd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41a3d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d85b41", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#8641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d86941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#9a41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d841b2", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#418fd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#d84183", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#6441d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#43d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#9341d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#6bd841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d86941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#86d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#9a41d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#6441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#6441d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d86941", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41cbd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#6441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#6441d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#7841d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#4941d8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#6bd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#9ad841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d85b41", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#41d859", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d841b9", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#86d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d841b2", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d84183", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#6b41d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#41d2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84162", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#9ad841", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#d8415b", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#9a41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#6bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41d859", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#7841d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#414cd8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41cbd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41d84c", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#4152d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84162", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d841c0", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#41d852", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d84191", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41cbd8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#9341d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#4174d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#64d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#b541d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#41d845", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d85b41", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#c941d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d86941", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4195d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d86f41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d859", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d860", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d841d4", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d841c6", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#418fd8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d89141", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d89e41", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d874", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#417bd8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d888", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d8cd41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#4160d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8d441", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8a3", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41d8b0", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4145d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#6bd841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#4941d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d8c4", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#6441d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d8d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#7241d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#93d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#9a41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#9341d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#72d841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d8cb", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8d441", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#414cd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#5041d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41a3d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d86941", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8a9", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d8cd41", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41b0d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d859", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#7841d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#b541d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d641d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d89141", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d841c0", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41d852", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d86941", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d84191", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#4941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#6441d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d88a41", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d874", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#57d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#a7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#4181d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d86941", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#9341d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#41d881", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#b541d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41d8b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41cbd8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d8a541", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#419cd8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#cf41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#4174d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#9341d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d87b", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41d881", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#418fd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41d8b0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d86941", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d8417d", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#a7d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#9341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#414cd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#93d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41cbd8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84162", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#6441d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d84141", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d8b941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d86941", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d841c6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d86941", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#64d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8d441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d86f41", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d87641", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#d87d41", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#d88341", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d89141", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d89841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d8a541", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d8b241", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8c041", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d8c641", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d8d441", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#c2d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#bbd841", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#a0d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#93d841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#6bd841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#5ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#57d841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#50d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#49d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d859", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#41d86d", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d874", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d895", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d89c", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8a3", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41d8b0", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41cbd8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41b0d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4195d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#4188d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#4181d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#4174d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#414cd8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4145d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#4941d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#5e41d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#5741d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#6441d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#7241d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#7841d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#7f41d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#9341d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#a741d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#ae41d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#bb41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#b541d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d641d8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d841cd", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d841c6", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d841ac", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d841b2", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d841a5", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8419e", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d84198", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d84176", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84155", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#4181d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#4159d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41d8b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d86941", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d841a5", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d859", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d6d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#49d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41b0d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84162", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#6bd841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d84198", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d8ac41", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#9341d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#416dd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8d441", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#41d8d2", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#43d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#57d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#9341d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41d881", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#4160d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d866", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#c9d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d841c6", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#93d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41d8b0", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84155", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d86241", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#9a41d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84176", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#a741d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#b5d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#41d86d", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d84147", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d86f41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d841c6", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#418fd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d888", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#64d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#6bd841", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v5x.json b/docs/public/middleware/graph_px4_fmu-v5x.json new file mode 100644 index 0000000000..95dd212785 --- /dev/null +++ b/docs/public/middleware/graph_px4_fmu-v5x.json @@ -0,0 +1 @@ +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#d84177", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d8415c", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d84177", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#c641d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#c641d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#abd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4cd841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#97d841", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d8bb41", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d84155", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d8bb41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#abd841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d8bb41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#bf41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#418ed8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#abd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#5941d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#9741d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d841bb", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#90d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41bdd8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41a9d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d88441", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#4541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#5341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d8d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#ab41d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#59d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d86941", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#75d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#67d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d850", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d84199", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8417e", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d84170", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#b2d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d84147", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#41d1d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#bfd841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841a6", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d879", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4187d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#bfd841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#89d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#b9d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d865", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#419bd8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#d8d641", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#41d8d1", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#d841a0", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d8af", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41afd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#cd41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#9041d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d880", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41d89b", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#4157d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#d88b41", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d4d841", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41d8cb", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d84192", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#6741d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#bfd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41a2d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d841c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#97d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#b941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#75d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d841d6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#6ed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41a9d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#4180d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#53d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#4165d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#415ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d850", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d87e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d86c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d872", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#d88b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#414ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#4c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#4143d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d8a641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8c841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d8c241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#8941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d8a2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#a441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#a4d841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4187d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41d843", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#b9d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d872", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841a6", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84162", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#b941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d841cf", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d86241", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d841c2", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d841bb", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#4157d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#4150d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d89241", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#4143d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d887", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d8b6", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41c4d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d841c8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41d88e", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d85541", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#45d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4194d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d84170", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#4172d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d8cf41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4cd841", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7541d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#41d857", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41d88e", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#9d41d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#416cd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#82d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d872", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#60d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#b241d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#75d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d8b441", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d86241", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41c4d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84e41", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#bfd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d879", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d89941", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#41cbd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d8414e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d8414e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d8414e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d8b441", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d850", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d87741", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d85e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#cdd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#41d8d1", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41c4d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84e41", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#bfd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d87041", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41c4d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#bfd841", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d84155", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d879", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d850", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41d894", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d84177", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#cdd841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d841bb", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d87741", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#41d88e", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#abd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8418b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84e41", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#75d841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d841d6", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#6ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d87041", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#4157d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d89941", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d8a641", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#6741d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d8418b", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41d894", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d8af", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#bfd841", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#a441d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#ab41d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#82d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41d88e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#75d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#67d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#41d8d1", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d84147", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#41d8d1", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d84177", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#c641d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84e41", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#a4d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#75d841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41a9d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41a2d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#67d841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4cd841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#45d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#4172d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#415ed8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d841bb", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d850", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#4157d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d841ad", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#5341d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#5941d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#6741d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d8bb41", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d887", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d84199", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d84192", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#cdd841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d84170", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d8415c", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d8b6", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#b2d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8b441", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#416cd8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#82d841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d85c41", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d88441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#b241d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d841c8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d85541", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41d88e", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#d88b41", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4194d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d841ad", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#5941d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#d841a0", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d84170", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#41d8d1", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8b441", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#90d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d87741", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d894", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d894", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d872", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#6741d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#75d841", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#b2d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#d841b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#cdd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#6041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#4541d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#59d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#5941d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d8a2", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#4157d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#cdd841", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#4c41d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d894", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8b441", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#7bd841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#9d41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#41cbd8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#75d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d841b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#cdd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#5941d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#d841a0", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#45d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#75d841", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d850", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8b441", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d8c241", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8b441", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#41d84a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8b441", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41a2d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d89241", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#d88b41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d8cf41", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d8d641", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#cdd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#b9d841", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#9dd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#90d841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#41d857", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d85e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d8a2", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d8b6", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41bdd8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41afd8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#419bd8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#418ed8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#4541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#6041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#9041d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#9741d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#c641d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d441d8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#cd41d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8417e", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d84170", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d872", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#75d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#6041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#4157d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8b441", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d86941", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d841bb", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#4157d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#89d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d441d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#75d841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#b2d841", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d8c4", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#4150d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#d88b41", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#41d894", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#414ad8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d85e", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d841c8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d84169", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d85541", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#4541d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d8a041", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d84170", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#41cbd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41c4d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84e41", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#bfd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d857", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d84184", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#41b6d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d8cf41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#7bd841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41a2d8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#4179d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#4157d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d86c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#b9d841", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v6x.json b/docs/public/middleware/graph_px4_fmu-v6x.json new file mode 100644 index 0000000000..cdc717fa67 --- /dev/null +++ b/docs/public/middleware/graph_px4_fmu-v6x.json @@ -0,0 +1 @@ +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#4158d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d87241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d8ab41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#b0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#5b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#b041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84164", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#417cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d841b9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d841c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d858", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41bcd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#d85d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#69d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#6241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d86b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d851", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d898", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41d8bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d84179", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41a6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#7041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841ab", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#c5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#b7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#c541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d8416b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d84f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d85641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#5bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8419d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d87941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d87c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#62d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41c3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#4198d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#4191d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8415d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d8414f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d8c141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#41d86e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d891", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8b5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#4151d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#b741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d86441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d88841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#9bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#416ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#9b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d8b941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d8c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41b5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84172", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d84156", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#70d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#6941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d84188", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d89d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#6941d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#6941d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#9bd841", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8415d", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8415d", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#7e41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#41c3d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#41d84a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#419fd8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d84a", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41c3d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#419fd8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#b741d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d86441", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d841cf", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d841cf", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#b741d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#7e41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d841c1", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#b741d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#d85d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#9341d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#4191d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d891", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#414ad8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#b041d8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d8ae", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#62d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#b7d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41aed8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d89641", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#4198d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#93d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41d8bc", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8419d", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#69d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#a941d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#53d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#5bd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#417cd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d89d41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d843", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#6241d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#7741d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d88a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#9b41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841ab", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d8c841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d87241", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#d88141", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d841a4", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d8c3", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#d88841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#9b41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#a9d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d8414f", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#a2d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d8ab41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#8c41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d8414f", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d8416b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#85d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4175d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d8d1", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d4d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#ccd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d841c8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d851", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41a6d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d866", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d8a441", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8b5", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#5341d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d858", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#9b41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d85f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#62d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#d84841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41bcd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#85d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#77d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41aed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41a6d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#419fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d85641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#418ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#4183d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#4cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d841d6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#d841cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d841b9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41d84a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#4541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841b2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d8c141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#5b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#6241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d84196", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d84188", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#41d86e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d875", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d84181", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d88a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d84179", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d898", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#b0d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d84156", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#4c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d87241", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841b2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841ab", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d8ab41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84164", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84141", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#7ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d84f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#62d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d88f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d89641", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#cc41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#415fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d841d6", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#4158d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d843", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d851", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d8cf41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d87c", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8a6", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#5341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#41d89f", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#c5d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d8418f", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#4cd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#a941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84172", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#a241d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#bed841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841b2", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#7041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d8414f", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41d1d8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#6941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d87941", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#62d841", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#4158d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d87941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#41d8bc", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4175d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#9b41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d8b241", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#4151d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#419fd8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#419fd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#416ed8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d8b941", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d8b941", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d8b941", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d8b941", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d843", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#6241d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#62d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d841cf", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#62d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#62d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#62d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d87941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41d8bc", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4175d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#9b41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d8b241", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#4151d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#4151d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d87941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41d8bc", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#4175d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#9b41d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d86441", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#62d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d8b241", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d87941", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#6941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#62d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d8b241", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d8ca", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#9b41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#419fd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d87941", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4175d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#be41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d89641", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#4151d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d8b241", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d841b9", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d8b941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#41d851", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d8c841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#6241d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d8d641", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d84179", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#41d8bc", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#41d8ca", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#4c41d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#a2d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41d851", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d841a4", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d8c3", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#417cd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#4166d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#62d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#5bd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d841a4", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#6941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#62d841", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8415d", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#85d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d88a", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41cad8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#9bd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41b5d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#9341d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d85641", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#70d841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d84f41", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41aed8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#69d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d86b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#62d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#5bd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d87941", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#417cd8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#b741d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#416ed8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#be41d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d88f41", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d89d41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#415fd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#45d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d8b241", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#5341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#6241d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d85f", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#7041d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d87c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#c5d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#7e41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d898", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#41d89f", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8b5", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#b7d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#8541d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#bed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d8ae", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d8414f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#4166d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#c541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#62d841", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41d1d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8a6", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d851", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41bcd8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#a941d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#9341d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41a6d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d8418f", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#4cd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#a2d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84172", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#7e41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#62d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d87941", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d866", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#4198d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d851", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#6241d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#62d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d87241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d858", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#41d851", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41d858", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#6241d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#d89d41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d883", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#62d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41d851", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#93d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d858", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d843", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41d851", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#4183d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#85d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d88a", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#416ed8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#62d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41b5d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#62d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#7ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#a941d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#4166d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d883", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41d8d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#a2d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#c5d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d88a", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d8c141", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d87941", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#418ad8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#62d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#62d841", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d85f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d858", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#d85d41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d86b41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d87241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d87941", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d88841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d89d41", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d8a441", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d8ab41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d8b241", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#c5d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#a9d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#8cd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#7ed841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#85d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#62d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#5bd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d858", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#41d86e", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d87c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d88a", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d891", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#41d8ae", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d8c3", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d8d1", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#41cad8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41c3d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41a6d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#419fd8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#4198d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#4191d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#4183d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#417cd8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#415fd8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#4143d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#7741d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#8541d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#8c41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#9341d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#b041d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d841c1", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841b2", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8419d", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d84188", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d84181", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84172", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d8416b", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8415d", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d84156", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84148", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d87241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#bed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d858", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84164", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d851", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841ab", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#6241d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d883", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d851", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#93d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d851", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d8cf41", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d88141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#6241d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8419d", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41a6d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d89641", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#cc41d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d89d41", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d441d8", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d841d6", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#8c41d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d84196", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#5341d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d841cf", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#a941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41b5d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#416ed8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#70d841", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#6941d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d86b41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#c5d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84172", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d87941", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41b5d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#416ed8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#70d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#45d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#7ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d87941", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d8ab41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41d851", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#5b41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#6241d8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d85f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#b0d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d8c3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#62d841", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_sitl.json b/docs/public/middleware/graph_px4_sitl.json index 4b358194da..4099ac8ea8 100644 --- a/docs/public/middleware/graph_px4_sitl.json +++ b/docs/public/middleware/graph_px4_sitl.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_fake_magnetometer", "name": "fake_magnetometer", "type": "Module", "color": "#666666"}, {"id": "m_px4_mavlink_debug", "name": "px4_mavlink_debug", "type": "Module", "color": "#666666"}, {"id": "m_work_item_example", "name": "work_item_example", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_px4_simple_app", "name": "px4_simple_app", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_fake_imu", "name": "fake_imu", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#4179d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#89d841", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4194d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41d84a", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#6e41d8", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#abd841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d8a041", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#b9d841", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#4541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#75d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#6ed841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84169", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41d8a2", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d8a9", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#6e41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#4180d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#bfd841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41d843", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d8bb41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#5941d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#41d8b6", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8418b", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#a441d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#41d8d1", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#59d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#45d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d880", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#41d894", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d8c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#b9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#41d8cb", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d84170", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#6e41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#90d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#414ad8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d857", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d84147", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#82d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#41d85e", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4c41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d88441", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d84141", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#d85541", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#41a2d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#4cd841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#d841a6", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#419bd8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#414ad8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#7b41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d88441", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#7b41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d865", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#67d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d89241", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d84177", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#c6d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d87e41", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#4143d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#b2d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#418ed8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#41d8cb", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#45d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d8cf41", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#6041d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#415ed8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#414ad8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8a641", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#bfd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41bdd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41afd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41a9d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#53d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#ab41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d85c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d86941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#b241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d87041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4194d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d850", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#41d857", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#41d879", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#9741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d841d6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d841c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#d8ad41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d8b441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841c2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#4172d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#4157d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#b9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d8414e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#41d8cb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d8417e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#b2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#a4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#97d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#6741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#89d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#7bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#8941d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#82d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4c41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d84e41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#90d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d857", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#4150d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#4165d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d850", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#bf41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#d88b41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d89b", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d8a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d841cf", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d841c8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#41d8af", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#bfd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#5341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#6741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41cbd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#4143d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#8241d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8a641", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#5941d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#41d8b6", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#cd41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#41d1d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#4cd841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#d86241", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#d87741", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#cd41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#5941d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#41d1d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#d86241", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#d87741", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#cd41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#5941d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#41d1d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#d86241", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#d87741", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#4cd841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c2", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#abd841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41afd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#41d887", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#c641d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d84192", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d8c4", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#9041d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#d4d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#ab41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d86941", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#4194d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#b941d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#c641d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#d441d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#d8b441", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#d8bb41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#d8c841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#41d8b6", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d841ad", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#41d8d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#5941d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#a4d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#d84169", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d8415c", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#9dd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#d8414e", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#5941d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84169", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d841ad", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#7541d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d8bb41", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d841a0", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#c641d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d8b441", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4194d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#9dd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#53d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#d85c41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d86941", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#b941d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#c641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#d441d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#d8b441", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#d8c841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#416cd8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d84199", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#a4d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d8415c", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#9dd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#d8414e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#8941d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d8414e", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41afd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d8c841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d8d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#416cd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8415c", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#b941d8", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#41b6d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#60d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#abd841", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c2", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c2", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d88441", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d872", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d89941", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#abd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d84162", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#7b41d8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d8bb41", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#4187d8", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d841c8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#6e41d8", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#4194d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro_fifo", "color": "#416cd8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_esc_status", "color": "#d441d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_accel", "color": "#d8414e", "style": "dashed"}, {"source": "m_fake_magnetometer", "target": "t_sensor_mag", "color": "#9dd841", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_key_value", "color": "#97d841", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_value", "color": "#d87041", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_array", "color": "#d8d641", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_vect", "color": "#d841d6", "style": "dashed"}, {"source": "m_px4_simple_app", "target": "t_vehicle_attitude", "color": "#b9d841", "style": "dashed"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#4187d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#41d8cb", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d4d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d8a041", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#b9d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#8941d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#41d8cb", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41afd8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d841b4", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d84141", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d841a6", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#419bd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#b9d841", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#b9d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d841bb", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41b6d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41a9d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#59d841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41d843", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d872", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#7bd841", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d880", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#418ed8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#41d887", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d89941", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#4187d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d89b", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d8a041", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d841cf", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8a641", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d8b441", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d8cf41", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#415ed8", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#cdd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#41d8cb", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d84170", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#d88b41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#5941d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d8d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84169", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#9dd841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41c4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#4143d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d88441", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#abd841", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d84162", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d84199", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d8bd", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#4541d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#4143d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41afd8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#41d887", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#b2d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#4187d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#419bd8", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d841a0", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d8a041", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d86941", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#9041d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#6ed841", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#4187d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#41d8cb", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#b9d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d8a041", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#4187d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d857", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#4150d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8418b", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#4143d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#41d8af", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d841bb", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#4187d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#ab41d8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#4143d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#60d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#bfd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d8414e", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#9d41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#41d8c4", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#416cd8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d841b4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84169", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d84e41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#419bd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#cdd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d857", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d85c41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#41d8cb", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#b2d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41d8d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#4187d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41bdd8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#9741d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#bfd841", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#415ed8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#d88b41", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d8a041", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d8a641", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d8c841", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8d641", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#b9d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#9dd841", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#97d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#59d841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41d843", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41d85e", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41d8a2", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#41d8d1", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41cbd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41afd8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41a2d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#4179d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#4150d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#4c41d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#6041d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#c641d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d441d8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841c2", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d841b4", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d841a6", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#d84184", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d84177", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#b9d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#abd841", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#90d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d857", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d4d841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#4150d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#bfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#4143d8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#41d8cb", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d880", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#5341d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#41d8d1", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#b2d841", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#4187d8", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d850", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#4cd841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#6741d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#4187d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#41d879", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8a641", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#8941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#b9d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#41d88e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#5941d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#41d8b6", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#41a9d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#cd41d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#41d1d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#d84155", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#d86241", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#d87741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#41d857", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#41d8cb", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#b9d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#5941d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#cd41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#41a9d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#41d1d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#d84155", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#d86241", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#d87741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#41d857", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#41d8cb", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#b9d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#5941d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#cd41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#41a9d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#41d1d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#d84155", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#d86241", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#d87741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#41d857", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#41d857", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#9d41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#c641d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#60d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#a4d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#59d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#9dd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d8414e", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#9041d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#4187d8", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#8241d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#d89241", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#5941d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#4187d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#414ad8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#c6d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41bdd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#d8bb41", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#d84147", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#8241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#5941d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#4187d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#414ad8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#c6d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41bdd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d8bb41", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#b941d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#7541d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d841ad", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#4187d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#9dd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d8414e", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#4150d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#41d857", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d89941", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#4187d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d8a041", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d8a9", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#4172d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d841a6", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#4c41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#d89941", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#41d8d1", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fake_magnetometer", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_work_item_example", "color": "#bfd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_work_item_example", "color": "#d8414e", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_fake_magnetometer", "name": "fake_magnetometer", "type": "Module", "color": "#666666"}, {"id": "m_px4_mavlink_debug", "name": "px4_mavlink_debug", "type": "Module", "color": "#666666"}, {"id": "m_work_item_example", "name": "work_item_example", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_px4_simple_app", "name": "px4_simple_app", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_fake_imu", "name": "fake_imu", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8418b", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d841c8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#75d841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d84177", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#97d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d87741", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#c6d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41d8b6", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#41d8a9", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#4180d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#7bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#82d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#41cbd8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d8cf41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#4143d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d841d6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d88441", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#4194d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d841c2", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d850", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#41d857", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d8bb41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#6041d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41d89b", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d85c41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d8b441", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#59d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d8a641", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#d4d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#d8a041", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#418ed8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d84e41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#41d872", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d88b41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#d84147", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#d89941", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d88b41", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#bf41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d8415c", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#9041d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d84192", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d841bb", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d86941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#41d843", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#6ed841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8a2", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d1d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#41d857", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d841c2", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#41d89b", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41b6d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#cd41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#89d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#4180d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d85c41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#4179d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#b241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8a2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#90d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d8d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#82d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#a441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#ab41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41afd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#b941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#59d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d87e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d841cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d841c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d841c2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#4165d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8ad41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#4157d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d8417e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d84170", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#4541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d8414e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#b9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#b2d841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#59d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d8b441", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d841b4", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84141", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#abd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#a4d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#9dd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#a441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#41bdd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#6ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#45d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#4180d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d89241", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#416cd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d85e", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#5341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d887", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d8c4", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#89d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#41a9d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#41a2d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#c641d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#9741d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#8241d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#d89941", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#41a9d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#41a2d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#c641d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#9741d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#8241d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#41a9d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#41a2d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#c641d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#9741d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#8241d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d89941", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#5941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#419bd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d88441", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d86241", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#7b41d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#4165d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#41d8a9", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d85541", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#67d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#4187d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#41d843", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84199", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#4c41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d8414e", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#41d894", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#41d8a9", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#6741d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#67d841", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#41d8cb", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d85541", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#41d8d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#ab41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#4187d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84199", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#d8417e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#4c41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d8414e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#b2d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a0", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84199", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#419bd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#4187d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d85541", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d894", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#bfd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#8941d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d88b41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#414ad8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d8c841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#416cd8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_esc_status", "color": "#4c41d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_fake_magnetometer", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_value", "color": "#4157d8", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_key_value", "color": "#b941d8", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_array", "color": "#d87e41", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_vect", "color": "#d8ad41", "style": "dashed"}, {"source": "m_px4_simple_app", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d8af", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d879", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d841c2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d84a", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#b2d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8d641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d879", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#419bd8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d84e41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#418ed8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d841c2", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84184", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41d89b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d841c2", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d84a", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d879", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#41d843", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#8941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d8af", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#a4d841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#90d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#89d841", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d1d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#6ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#53d841", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#cd41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d88441", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d441d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d841c2", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d850", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d89241", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d841a6", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#4165d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#4150d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#414ad8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d84177", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#4541d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#4c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d879", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#5941d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#bfd841", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d887", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41d89b", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84169", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#7bd841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d88b41", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d8c841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d8cf41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84184", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d841ad", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#416cd8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8a2", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#419bd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d88441", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#41d8cb", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#6ed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d894", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d8af", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#4180d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d1d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d8af", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d84177", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#41d8af", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#41d84a", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#d84177", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#b241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#7bd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#6ed841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#60d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#b241d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41afd8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#45d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#6e41d8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d84a", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#41d843", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d841a6", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d88441", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#9d41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#7541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#5341d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#41d8a9", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#59d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d88441", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#7bd841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84184", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d84177", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d879", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d8a2", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d841c2", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#6ed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d8af", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#4165d8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#4cd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#4180d8", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#4179d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d88441", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d89241", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8ad41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d8c241", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#a4d841", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#97d841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#9dd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#7bd841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#41d857", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d879", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d887", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8a2", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#41cbd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#419bd8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#4180d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#4150d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#4c41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#5341d8", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#6041d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#8941d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#9041d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#a441d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#b241d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d441d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d841c2", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#d84199", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d84192", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84184", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d84177", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d8415c", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84169", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#b241d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#6ed841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#6ed841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#60d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#b241d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8a2", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d8af", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#9dd841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#6041d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d441d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d841d6", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d85e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#4180d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d841c2", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d84a", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#41d8af", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#89d841", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d84170", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#b2d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d84162", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#4541d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#cdd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#41d879", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#41a2d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#c641d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#41a9d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#9741d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d841c2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#8241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#b241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d84162", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#4541d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#41a9d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#41d879", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#41a2d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#c641d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#9741d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d841c2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#8241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#b241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d84162", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#4541d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#41a9d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#41d879", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#41a2d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#c641d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#9741d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d841c2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#8241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d879", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41d865", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#8941d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d88441", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#4194d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d8414e", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#7bd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#7541d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#4150d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#7b41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#4180d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#41d8af", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#4172d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#d8415c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#41d8af", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#d8a641", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d8c4", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#d85c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#4143d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#b241d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#4172d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d8af", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d8a641", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d8c4", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d85c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#4143d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#67d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d8af", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#4cd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#60d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d879", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#4179d8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#415ed8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d84177", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#53d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d841d6", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fake_magnetometer", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_work_item_example", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_work_item_example", "color": "#d841a6", "style": "normal"}]} \ No newline at end of file diff --git a/docs/uk/_sidebar.md b/docs/uk/_sidebar.md index 06be432d30..c676939e34 100644 --- a/docs/uk/_sidebar.md +++ b/docs/uk/_sidebar.md @@ -42,8 +42,9 @@ - [MindRacer BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [MindRacer 210](/complete_vehicles_mc/mindracer210.md) - [NanoMind 110](/complete_vehicles_mc/nanomind110.md) - - [Holybro Kopis 2](/complete_vehicles_mc/holybro_kopis2.md) - [Bitcraze Crazyflie 2.1](/complete_vehicles_mc/crazyflie21.md) + - [Holybro Kopis 2](/complete_vehicles_mc/holybro_kopis2.md) + - [Amov F410 Drone](/complete_vehicles_mc/amov_F410_drone.md) - [Набори](/frames_multicopter/kits.md) - [X500 v2 (Pixhawk 6C)](/frames_multicopter/holybro_x500v2_pixhawk6c.md) - [X500 v2 (Pixhawk 5X)](/frames_multicopter/holybro_x500V2_pixhawk5x.md) @@ -182,6 +183,7 @@ - [Holybro Kakute H7v2](/flight_controller/kakuteh7v2.md) - [Holybro Kakute H7mini](/flight_controller/kakuteh7mini.md) - [Holybro Kakute H7](/flight_controller/kakuteh7.md) + - [Holybro Kakute H7 Wing](/flight_controller/kakuteh7-wing.md) - [Holybro Durandal](/flight_controller/durandal.md) - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) @@ -253,6 +255,7 @@ - [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](/dronecan/avanon_laser_interface.md) - [GNSS (GPS)](/gps_compass/index.md) - [ARK GPS (CAN)](/dronecan/ark_gps.md) + - [ARK SAM GPS](/gps_compass/ark_sam_gps.md) - [ARK TESEO GPS](/dronecan/ark_teseo_gps.md) - [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md) - [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md) @@ -314,6 +317,7 @@ - [Джойстики](/config/joystick.md) - [Посилання даних](/data_links/index.md) - [MAVLink Telemetry (OSD/GCS)](/peripherals/mavlink_peripherals.md) + - [Телеметричні радіостанції](/telemetry/index.md) - [SiK Radio](/telemetry/sik_radio.md) - [Телеметричне радіо RFD900 (SiK)](/telemetry/rfd900_telemetry.md) @@ -326,9 +330,13 @@ - [ARK Electron Microhard Серійне Телеметрійне Радіо](/telemetry/ark_microhard_serial.md) - [Holybro Microhard P900 Телеметрійне Радіо](/telemetry/holybro_microhard_p900_radio.md) - [CUAV P8 Телеметрійне радіо](/telemetry/cuav_p8_radio.md) + - [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md) - [Holybro XBP9X - Припинено](/telemetry/holybro_xbp9x_radio.md) + - [FrSky телеметрія](/peripherals/frsky_telemetry.md) + - [TBS Crossfire (CRSF) телеметрія](/telemetry/crsf_telemetry.md) + - [Супутниковий зв'язок (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) - [Енергетичні системи](/power_systems/index.md) - [Налаштування оцінки батареї](/config/battery.md) @@ -637,6 +645,7 @@ - [PowerButtonState](/msg_docs/PowerButtonState.md) - [PowerMonitor](/msg_docs/PowerMonitor.md) - [PpsCapture](/msg_docs/PpsCapture.md) + - [PurePursuitStatus](/msg_docs/PurePursuitStatus.md) - [PwmInput](/msg_docs/PwmInput.md) - [Px4ioStatus](/msg_docs/Px4ioStatus.md) - [QshellReq](/msg_docs/QshellReq.md) @@ -710,6 +719,10 @@ - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [Повідомлення MAVLink](/middleware/mavlink.md) + - [Adding Messages](/mavlink/adding_messages.md) + - [Streaming Messages](/mavlink/streaming_messages.md) + - [Receiving Messages](/mavlink/receiving_messages.md) + - [Custom MAVLink Messages](/mavlink/custom_messages.md) - [Standard Modes Protocol](/mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md) - [Модулі & Команди](/modules/modules_main.md) @@ -798,8 +811,10 @@ - [Тест MC_05 - Політ у приміщенні (ручні режими)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [Модульні Тести](/test_and_ci/unit_tests.md) - [Безперервна інтеграція](/test_and_ci/continous_integration.md) - - [MAVSDK Тестування інтеграції ](/test_and_ci/integration_testing_mavsdk.md) - - [ROS Тестування інтеграції ](/test_and_ci/integration_testing.md) + - [Integration Testing](/test_and_ci/integration_testing.md) + - [MAVSDK Тестування інтеграції ](/test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](/test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](/test_and_ci/integration_testing_ros1_mavros.md) - [Докер-контейнер](/test_and_ci/docker.md) - [Підтримка](/test_and_ci/maintenance.md) @@ -840,4 +855,4 @@ - [1.15 (stable)](/releases/1.15.md) - [1.14](/releases/1.14.md) - [1.13](/releases/1.13.md) - - [1.12](/releases/1.12.md) \ No newline at end of file + - [1.12](/releases/1.12.md) diff --git a/docs/zh/_sidebar.md b/docs/zh/_sidebar.md index 97c92918d6..fbb93d9a0a 100644 --- a/docs/zh/_sidebar.md +++ b/docs/zh/_sidebar.md @@ -42,8 +42,9 @@ - [MindRacer BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [MindRacer 210](/complete_vehicles_mc/mindracer210.md) - [NanoMind 110](/complete_vehicles_mc/nanomind110.md) - - [Holybro Kopis 2](/complete_vehicles_mc/holybro_kopis2.md) - [Bitcraze Crazyflie 2.1](/complete_vehicles_mc/crazyflie21.md) + - [Holybro Kopis 2](/complete_vehicles_mc/holybro_kopis2.md) + - [Amov F410 Drone](/complete_vehicles_mc/amov_F410_drone.md) - [套装](/frames_multicopter/kits.md) - [X500 v2 (Pixhawk 6C)](/frames_multicopter/holybro_x500v2_pixhawk6c.md) - [X500 v2 (Pixhawk 5X)](/frames_multicopter/holybro_x500V2_pixhawk5x.md) @@ -182,6 +183,7 @@ - [Holybro Kakute H7v2](/flight_controller/kakuteh7v2.md) - [Holybro Kakute H7mini](/flight_controller/kakuteh7mini.md) - [Holybro Kakute H7](/flight_controller/kakuteh7.md) + - [Holybro Kakute H7 Wing](/flight_controller/kakuteh7-wing.md) - [Holybro Durandal](/flight_controller/durandal.md) - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) @@ -253,6 +255,7 @@ - [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](/dronecan/avanon_laser_interface.md) - [GNSS (GPS)](/gps_compass/index.md) - [ARK GPS (CAN)](/dronecan/ark_gps.md) + - [ARK SAM GPS](/gps_compass/ark_sam_gps.md) - [ARK TESEO GPS](/dronecan/ark_teseo_gps.md) - [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md) - [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md) @@ -314,6 +317,7 @@ - [Joysticks](/config/joystick.md) - [Data Links](/data_links/index.md) - [MAVLink 回传(OSD/GCS)](/peripherals/mavlink_peripherals.md) + - [数传电台](/telemetry/index.md) - [SiK 电台](/telemetry/sik_radio.md) - [RFD900 (SiK) 数传电台](/telemetry/rfd900_telemetry.md) @@ -326,9 +330,13 @@ - [ARK Electron Microhard Serial Telemetry Radio](/telemetry/ark_microhard_serial.md) - [Holybro Microhard P900 Telemetry Radio](/telemetry/holybro_microhard_p900_radio.md) - [CUAV P8 Telemetry Radio](/telemetry/cuav_p8_radio.md) + - [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md) - [HolyBro XBP9X - Discontinued](/telemetry/holybro_xbp9x_radio.md) + - [睿思凯数传](/peripherals/frsky_telemetry.md) + - [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md) + - [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) - [Power Systems](/power_systems/index.md) - [Battery Estimation Tuning](/config/battery.md) @@ -637,6 +645,7 @@ - [PowerButtonState](/msg_docs/PowerButtonState.md) - [PowerMonitor](/msg_docs/PowerMonitor.md) - [PpsCapture](/msg_docs/PpsCapture.md) + - [PurePursuitStatus](/msg_docs/PurePursuitStatus.md) - [PwmInput](/msg_docs/PwmInput.md) - [Px4ioStatus](/msg_docs/Px4ioStatus.md) - [QshellReq](/msg_docs/QshellReq.md) @@ -710,6 +719,10 @@ - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [MAVLink通讯](/middleware/mavlink.md) + - [Adding Messages](/mavlink/adding_messages.md) + - [Streaming Messages](/mavlink/streaming_messages.md) + - [Receiving Messages](/mavlink/receiving_messages.md) + - [Custom MAVLink Messages](/mavlink/custom_messages.md) - [Standard Modes Protocol](/mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md) - [模块 & 命令](/modules/modules_main.md) @@ -798,8 +811,10 @@ - [测试 MC_05-室内飞行(手动模式)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [单元测试](/test_and_ci/unit_tests.md) - [持续集成](/test_and_ci/continous_integration.md) - - [MAVSDK集成测试](/test_and_ci/integration_testing_mavsdk.md) - - [ROS集成测试](/test_and_ci/integration_testing.md) + - [Integration Testing](/test_and_ci/integration_testing.md) + - [MAVSDK集成测试](/test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](/test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](/test_and_ci/integration_testing_ros1_mavros.md) - [Docker 容器](/test_and_ci/docker.md) - [维护](/test_and_ci/maintenance.md) @@ -840,4 +855,4 @@ - [1.15 (stable)](/releases/1.15.md) - [1.14](/releases/1.14.md) - [1.13](/releases/1.13.md) - - [1.12](/releases/1.12.md) \ No newline at end of file + - [1.12](/releases/1.12.md) From 2cc9221aae120948db8f09fdc519ac1ae4109f55 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Wed, 21 May 2025 11:49:26 +0200 Subject: [PATCH 013/130] Revert "add flash-analysis for auterion_fmu-v6s board (#24885)" (#24896) This reverts commit 9e45f077b189806bdd1b1ef1d2b3b6fe5e99f3aa. --- boards/auterion/fmu-v6s/flash-analysis.px4board | 1 - .../fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld | 6 ------ 2 files changed, 7 deletions(-) delete mode 100644 boards/auterion/fmu-v6s/flash-analysis.px4board delete mode 100644 boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld diff --git a/boards/auterion/fmu-v6s/flash-analysis.px4board b/boards/auterion/fmu-v6s/flash-analysis.px4board deleted file mode 100644 index 30717ad93c..0000000000 --- a/boards/auterion/fmu-v6s/flash-analysis.px4board +++ /dev/null @@ -1 +0,0 @@ -CONFIG_BOARD_LINKER_PREFIX="flash-analysis" diff --git a/boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld b/boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld deleted file mode 100644 index 5df2f5180a..0000000000 --- a/boards/auterion/fmu-v6s/nuttx-config/scripts/flash-analysis-script.ld +++ /dev/null @@ -1,6 +0,0 @@ -INCLUDE "script.ld" - -MEMORY -{ - FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 10080K -} From 508dc030b85fde15e3b25c4790f92e0bc7fe5ad9 Mon Sep 17 00:00:00 2001 From: Dawid Rudy Date: Fri, 25 Apr 2025 19:58:48 +0200 Subject: [PATCH 014/130] Smooth yaw by limiting acceleration --- .../tasks/Auto/FlightTaskAuto.cpp | 47 ++++++++----------- .../tasks/Auto/FlightTaskAuto.hpp | 7 +-- 2 files changed, 23 insertions(+), 31 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index f23ec7dc02..120da92561 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -70,7 +70,8 @@ bool FlightTaskAuto::activate(const trajectory_setpoint_s &last_setpoint) _position_smoothing.reset(accel_prev, vel_prev, pos_prev); - _yaw_sp_prev = PX4_ISFINITE(last_setpoint.yaw) ? last_setpoint.yaw : _yaw; + const float heading = PX4_ISFINITE(last_setpoint.yaw) ? last_setpoint.yaw : _yaw; + _heading_smoothing.reset(heading, 0.f); _updateTrajConstraints(); _is_emergency_braking_active = false; _time_last_cruise_speed_override = 0; @@ -190,16 +191,14 @@ bool FlightTaskAuto::update() // no valid heading -> generate heading in this flight task // Generate heading along trajectory if possible, otherwise hold the previous yaw setpoint if (!_generateHeadingAlongTraj()) { - _yaw_setpoint = PX4_ISFINITE(_yaw_sp_prev) ? _yaw_sp_prev : _yaw; + _yaw_setpoint = _yaw; } } // update previous type _type_previous = _type; - // If the FlightTask generates a yaw or a yawrate setpoint that exceeds this value - // it will see its setpoint constrained here - _limitYawRate(); + _smoothYaw(); _constraints.want_takeoff = _checkTakeoff(); @@ -257,7 +256,7 @@ void FlightTaskAuto::_prepareLandSetpoints() if (sticks_xy.longerThan(FLT_EPSILON)) { // Ensure no unintended yawing when nudging horizontally during initial heading alignment - _land_heading = _yaw_sp_prev; + _land_heading = _yaw; } rcHelpModifyYaw(_land_heading); @@ -300,39 +299,25 @@ void FlightTaskAuto::_prepareLandSetpoints() _gear.landing_gear = landing_gear_s::GEAR_DOWN; } -void FlightTaskAuto::_limitYawRate() +void FlightTaskAuto::_smoothYaw() { const float yawrate_max = math::radians(_param_mpc_yawrauto_max.get()); _yaw_sp_aligned = true; - if (PX4_ISFINITE(_yaw_setpoint) && PX4_ISFINITE(_yaw_sp_prev)) { - // Limit the rate of change of the yaw setpoint - const float dyaw_desired = matrix::wrap_pi(_yaw_setpoint - _yaw_sp_prev); - const float dyaw_max = yawrate_max * _deltatime; - const float dyaw = math::constrain(dyaw_desired, -dyaw_max, dyaw_max); - const float yaw_setpoint_sat = matrix::wrap_pi(_yaw_sp_prev + dyaw); + if (PX4_ISFINITE(_yaw_setpoint)) { + _heading_smoothing.update(_yaw_setpoint, _deltatime); + float yaw_sp_prev = _yaw_setpoint; + _yaw_setpoint = _heading_smoothing.getSmoothedHeading(); + _yawspeed_setpoint = _heading_smoothing.getSmoothedHeadingRate(); // The yaw setpoint is aligned when it is within tolerance - _yaw_sp_aligned = fabsf(matrix::wrap_pi(_yaw_setpoint - yaw_setpoint_sat)) < math::radians(_param_mis_yaw_err.get()); - - _yaw_setpoint = yaw_setpoint_sat; - - if (!PX4_ISFINITE(_yawspeed_setpoint) && (_deltatime > FLT_EPSILON)) { - // Create a feedforward using the filtered derivative - _yawspeed_filter.setParameters(_deltatime, .2f); - _yawspeed_filter.update(dyaw / _deltatime); - _yawspeed_setpoint = _yawspeed_filter.getState(); - } + _yaw_sp_aligned = fabsf(matrix::wrap_pi(yaw_sp_prev - _yaw_setpoint)) < math::radians(_param_mis_yaw_err.get()); } - _yaw_sp_prev = PX4_ISFINITE(_yaw_setpoint) ? _yaw_setpoint : _yaw; - if (PX4_ISFINITE(_yawspeed_setpoint)) { // The yaw setpoint is aligned when its rate is not saturated _yaw_sp_aligned = _yaw_sp_aligned && (fabsf(_yawspeed_setpoint) < yawrate_max); - - _yawspeed_setpoint = math::constrain(_yawspeed_setpoint, -yawrate_max, yawrate_max); } } @@ -725,7 +710,7 @@ void FlightTaskAuto::_ekfResetHandlerVelocityZ(float delta_vz) void FlightTaskAuto::_ekfResetHandlerHeading(float delta_psi) { - _yaw_sp_prev += delta_psi; + _yaw_setpoint += delta_psi; } void FlightTaskAuto::_checkEmergencyBraking() @@ -835,6 +820,12 @@ void FlightTaskAuto::_updateTrajConstraints() // correction required by the altitude/vertical position controller _constraints.speed_down = math::max(_constraints.speed_down, 1.2f * _param_mpc_z_v_auto_dn.get());; _constraints.speed_up = math::max(_constraints.speed_up, 1.2f * _param_mpc_z_v_auto_up.get());; + + // Update constrains of heading smoothing + const float yawrate_max = math::radians(_param_mpc_yawrauto_max.get()); + const float yawrate_acc = math::radians(_param_mpc_yawrauto_acc.get()); + _heading_smoothing.setMaxHeadingRate(yawrate_max); + _heading_smoothing.setMaxHeadingAccel(yawrate_acc); } bool FlightTaskAuto::_highEnoughForLandingGear() diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp index c177a74d5f..27f49a3cfc 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp @@ -52,6 +52,7 @@ #include #include "Sticks.hpp" #include "StickAccelerationXY.hpp" +#include "HeadingSmoothing.hpp" /** * This enum has to agree with position_setpoint_s type definition @@ -136,8 +137,7 @@ protected: State _current_state{State::none}; float _target_acceptance_radius{0.0f}; /**< Acceptances radius of the target */ - float _yaw_sp_prev{NAN}; - AlphaFilter _yawspeed_filter; + HeadingSmoothing _heading_smoothing; bool _yaw_sp_aligned{false}; PositionSmoothing _position_smoothing; @@ -156,6 +156,7 @@ protected: (ParamFloat) _param_nav_mc_alt_rad, //vertical acceptance radius at which waypoints are updated (ParamInt) _param_mpc_yaw_mode, // defines how heading is executed, + (ParamFloat) _param_mpc_yawrauto_acc, (ParamFloat) _param_mpc_yawrauto_max, (ParamFloat) _param_mis_yaw_err, // yaw-error threshold (ParamFloat) _param_mpc_acc_hor, // acceleration in flight @@ -201,7 +202,7 @@ private: matrix::Vector3f _initial_land_position; - void _limitYawRate(); /**< Limits the rate of change of the yaw setpoint. */ + void _smoothYaw(); /**< Smoothen the yaw setpoint. */ bool _evaluateTriplets(); /**< Checks and sets triplets. */ bool _isFinite(const position_setpoint_s &sp); /**< Checks if all waypoint triplets are finite. */ bool _evaluateGlobalReference(); /**< Check is global reference is available. */ From 70ad2e6fe5b96e2a3e58ab4d9d141097438152ba Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 8 May 2025 18:23:32 +0200 Subject: [PATCH 015/130] FlightTaskAuto: Smooth yaw follow-up, bring back necessary previous yaw setpoint and reset smoothing when yaw is not locked --- .../tasks/Auto/FlightTaskAuto.cpp | 29 ++++++++++--------- .../tasks/Auto/FlightTaskAuto.hpp | 3 +- 2 files changed, 18 insertions(+), 14 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index 120da92561..1ae5d733f0 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -70,8 +70,10 @@ bool FlightTaskAuto::activate(const trajectory_setpoint_s &last_setpoint) _position_smoothing.reset(accel_prev, vel_prev, pos_prev); - const float heading = PX4_ISFINITE(last_setpoint.yaw) ? last_setpoint.yaw : _yaw; - _heading_smoothing.reset(heading, 0.f); + _yaw_setpoint_previous = last_setpoint.yaw; + _heading_smoothing.reset(PX4_ISFINITE(last_setpoint.yaw) ? last_setpoint.yaw : _yaw, + PX4_ISFINITE(last_setpoint.yawspeed) ? last_setpoint.yawspeed : 0.f); + _updateTrajConstraints(); _is_emergency_braking_active = false; _time_last_cruise_speed_override = 0; @@ -191,7 +193,7 @@ bool FlightTaskAuto::update() // no valid heading -> generate heading in this flight task // Generate heading along trajectory if possible, otherwise hold the previous yaw setpoint if (!_generateHeadingAlongTraj()) { - _yaw_setpoint = _yaw; + _yaw_setpoint = _yaw_setpoint_previous; } } @@ -256,7 +258,7 @@ void FlightTaskAuto::_prepareLandSetpoints() if (sticks_xy.longerThan(FLT_EPSILON)) { // Ensure no unintended yawing when nudging horizontally during initial heading alignment - _land_heading = _yaw; + _land_heading = _yaw_setpoint_previous; } rcHelpModifyYaw(_land_heading); @@ -302,19 +304,26 @@ void FlightTaskAuto::_prepareLandSetpoints() void FlightTaskAuto::_smoothYaw() { const float yawrate_max = math::radians(_param_mpc_yawrauto_max.get()); + _heading_smoothing.setMaxHeadingRate(yawrate_max); + _heading_smoothing.setMaxHeadingAccel(math::radians(_param_mpc_yawrauto_acc.get())); _yaw_sp_aligned = true; if (PX4_ISFINITE(_yaw_setpoint)) { + const float yaw_sp_unsmoothed = _yaw_setpoint; _heading_smoothing.update(_yaw_setpoint, _deltatime); - float yaw_sp_prev = _yaw_setpoint; _yaw_setpoint = _heading_smoothing.getSmoothedHeading(); _yawspeed_setpoint = _heading_smoothing.getSmoothedHeadingRate(); // The yaw setpoint is aligned when it is within tolerance - _yaw_sp_aligned = fabsf(matrix::wrap_pi(yaw_sp_prev - _yaw_setpoint)) < math::radians(_param_mis_yaw_err.get()); + _yaw_sp_aligned = fabsf(matrix::wrap_pi(yaw_sp_unsmoothed - _yaw_setpoint)) < math::radians(_param_mis_yaw_err.get()); + + } else { + _heading_smoothing.reset(_yaw, 0.f); } + _yaw_setpoint_previous = _yaw_setpoint; + if (PX4_ISFINITE(_yawspeed_setpoint)) { // The yaw setpoint is aligned when its rate is not saturated _yaw_sp_aligned = _yaw_sp_aligned && (fabsf(_yawspeed_setpoint) < yawrate_max); @@ -710,7 +719,7 @@ void FlightTaskAuto::_ekfResetHandlerVelocityZ(float delta_vz) void FlightTaskAuto::_ekfResetHandlerHeading(float delta_psi) { - _yaw_setpoint += delta_psi; + _yaw_setpoint_previous += delta_psi; } void FlightTaskAuto::_checkEmergencyBraking() @@ -820,12 +829,6 @@ void FlightTaskAuto::_updateTrajConstraints() // correction required by the altitude/vertical position controller _constraints.speed_down = math::max(_constraints.speed_down, 1.2f * _param_mpc_z_v_auto_dn.get());; _constraints.speed_up = math::max(_constraints.speed_up, 1.2f * _param_mpc_z_v_auto_up.get());; - - // Update constrains of heading smoothing - const float yawrate_max = math::radians(_param_mpc_yawrauto_max.get()); - const float yawrate_acc = math::radians(_param_mpc_yawrauto_acc.get()); - _heading_smoothing.setMaxHeadingRate(yawrate_max); - _heading_smoothing.setMaxHeadingAccel(yawrate_acc); } bool FlightTaskAuto::_highEnoughForLandingGear() diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp index 27f49a3cfc..00610d910c 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp @@ -47,12 +47,12 @@ #include #include #include +#include #include #include #include #include "Sticks.hpp" #include "StickAccelerationXY.hpp" -#include "HeadingSmoothing.hpp" /** * This enum has to agree with position_setpoint_s type definition @@ -137,6 +137,7 @@ protected: State _current_state{State::none}; float _target_acceptance_radius{0.0f}; /**< Acceptances radius of the target */ + float _yaw_setpoint_previous{NAN}; /**< Used because _yaw_setpoint is overwritten in multiple places */ HeadingSmoothing _heading_smoothing; bool _yaw_sp_aligned{false}; From a8f5b6dc1b57f9e33a4df6b342271fdce3afe2dc Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 8 May 2025 20:53:38 +0200 Subject: [PATCH 016/130] FlightTaskOrbit: also use HeadingSmoothing to avoid steps during the approach --- .../tasks/Orbit/FlightTaskOrbit.cpp | 15 +++++++++++---- .../tasks/Orbit/FlightTaskOrbit.hpp | 4 +++- 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index 3136c98051..70b5835a6c 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -179,8 +179,8 @@ bool FlightTaskOrbit::activate(const trajectory_setpoint_s &last_setpoint) _orbit_velocity = 1.f; _center = _position; _initial_heading = _yaw; - _slew_rate_yaw.setForcedValue(_yaw); - _slew_rate_yaw.setSlewRate(math::radians(_param_mpc_yawrauto_max.get())); + _heading_smoothing.reset(PX4_ISFINITE(last_setpoint.yaw) ? last_setpoint.yaw : _yaw, + PX4_ISFINITE(last_setpoint.yawspeed) ? last_setpoint.yawspeed : 0.f); _slew_rate_velocity.setSlewRate(_param_mpc_acc_hor.get()); // need a valid position and velocity @@ -238,7 +238,14 @@ bool FlightTaskOrbit::update() } // Apply yaw smoothing - _yaw_setpoint = _slew_rate_yaw.update(_yaw_setpoint, _deltatime); + _heading_smoothing.setMaxHeadingRate(math::radians(_param_mpc_yawrauto_max.get())); + _heading_smoothing.setMaxHeadingAccel(math::radians(_param_mpc_yawrauto_acc.get())); + _heading_smoothing.update(_yaw_setpoint, _deltatime); + _yaw_setpoint = _heading_smoothing.getSmoothedHeading(); + + if (_in_circle_approach) { // don't override feed-forward which is already calculated for circling + _yawspeed_setpoint = _heading_smoothing.getSmoothedHeadingRate(); + } // publish information to UI sendTelemetry(); @@ -362,7 +369,7 @@ void FlightTaskOrbit::_generate_circle_yaw_setpoints() case orbit_status_s::ORBIT_YAW_BEHAVIOUR_UNCONTROLLED: // no yaw setpoint _yaw_setpoint = NAN; - _yawspeed_setpoint = NAN; + _yawspeed_setpoint = 0.f; // No yaw setpoint is invalid -> just brake to 0°/s break; case orbit_status_s::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE: diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp index 13e53bf83f..af4ddc67be 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #include #include @@ -127,7 +128,7 @@ private: bool _started_clockwise{true}; bool _currently_orbiting{false}; float _initial_heading = 0.f; /**< the heading of the drone when the orbit command was issued */ - SlewRateYaw _slew_rate_yaw; + HeadingSmoothing _heading_smoothing; SlewRate _slew_rate_velocity; orb_advert_t _mavlink_log_pub{nullptr}; @@ -138,6 +139,7 @@ private: (ParamInt) _param_mc_orbit_yaw_mod, (ParamFloat) _param_mpc_xy_cruise, /**< cruise speed for circle approach */ (ParamFloat) _param_mpc_yawrauto_max, + (ParamFloat) _param_mpc_yawrauto_acc, (ParamFloat) _param_mpc_xy_traj_p, (ParamFloat) _param_nav_mc_alt_rad, //vertical acceptance radius at which waypoints are updated From 30df381f0ee22c474fea760349459789bbab9577 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 8 May 2025 20:55:28 +0200 Subject: [PATCH 017/130] multicopter_autonomous_params: adjust yaw acceleration and maximum rate for exclusive use with HeadingSmoothing --- src/modules/mc_pos_control/multicopter_autonomous_params.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mc_pos_control/multicopter_autonomous_params.c b/src/modules/mc_pos_control/multicopter_autonomous_params.c index e2e453d975..4237c02a77 100644 --- a/src/modules/mc_pos_control/multicopter_autonomous_params.c +++ b/src/modules/mc_pos_control/multicopter_autonomous_params.c @@ -145,7 +145,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_ERR_MAX, 2.f); * @increment 5 * @group Multicopter Attitude Control */ -PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 45.f); +PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 60.f); /** * Maximum yaw acceleration in autonomous modes @@ -160,7 +160,7 @@ PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 45.f); * @increment 5 * @group Multicopter Attitude Control */ -PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_ACC, 60.f); +PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_ACC, 20.f); /** * Heading behavior in autonomous modes From 0b3b5d945073c336ce269cffa1bc0b18a4e9ddc3 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Thu, 15 May 2025 14:39:20 +0200 Subject: [PATCH 018/130] framework: only log "Failsafe activated" when failsafe action =! Warn. --- src/modules/commander/failsafe/framework.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 8d633e9f21..bdfe9fed97 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -238,6 +238,8 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action {events::Log::Critical, events::LogInternal::Warning}, "Failsafe activated: Autopilot disengaged, switching to {2}", mavlink_mode, failsafe_action); + mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); + } else { /* EVENT * @type append_health_and_arming_messages @@ -246,6 +248,8 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::ID("commander_failsafe_enter_generic"), {events::Log::Critical, events::LogInternal::Warning}, "Failsafe activated: switching to {2}", mavlink_mode, failsafe_action); + + mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); } } else { @@ -287,10 +291,11 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::ID("commander_failsafe_enter"), {events::Log::Critical, events::LogInternal::Warning}, "{3}: switching to {2}", mavlink_mode, failsafe_action, failsafe_cause); + + mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); } } - mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); } #endif /* EMSCRIPTEN_BUILD */ From d44991f33a47d9038e0fe125dd490882dde2c4f3 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Thu, 15 May 2025 14:40:25 +0200 Subject: [PATCH 019/130] batteryCheck: change log level to 'warning' for low and critical battery. --- .../commander/HealthAndArmingChecks/checks/batteryCheck.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index c20919ba56..0ac49e7a81 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -222,7 +222,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) log_level, "Low battery"); if (reporter.mavlink_log_pub()) { - mavlink_log_emergency(reporter.mavlink_log_pub(), "Low battery\t"); + mavlink_log_warning(reporter.mavlink_log_pub(), "Low battery\t"); } break; @@ -240,7 +240,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) log_level, "Critical battery"); if (reporter.mavlink_log_pub()) { - mavlink_log_emergency(reporter.mavlink_log_pub(), "Critical battery\t"); + mavlink_log_warning(reporter.mavlink_log_pub(), "Critical battery\t"); } break; From fa168c4d4f223f441a0c94acebbfd25317e5cb48 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Fri, 16 May 2025 11:12:14 +0200 Subject: [PATCH 020/130] address review comments --- .../HealthAndArmingChecks/checks/batteryCheck.cpp | 2 +- src/modules/commander/failsafe/framework.cpp | 10 ++++------ 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index 0ac49e7a81..daba5b5006 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -240,7 +240,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) log_level, "Critical battery"); if (reporter.mavlink_log_pub()) { - mavlink_log_warning(reporter.mavlink_log_pub(), "Critical battery\t"); + mavlink_log_critical(reporter.mavlink_log_pub(), "Critical battery\t"); } break; diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index bdfe9fed97..9e5b1bc62b 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -238,8 +238,6 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action {events::Log::Critical, events::LogInternal::Warning}, "Failsafe activated: Autopilot disengaged, switching to {2}", mavlink_mode, failsafe_action); - mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); - } else { /* EVENT * @type append_health_and_arming_messages @@ -248,8 +246,6 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::ID("commander_failsafe_enter_generic"), {events::Log::Critical, events::LogInternal::Warning}, "Failsafe activated: switching to {2}", mavlink_mode, failsafe_action); - - mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); } } else { @@ -291,13 +287,15 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action events::ID("commander_failsafe_enter"), {events::Log::Critical, events::LogInternal::Warning}, "{3}: switching to {2}", mavlink_mode, failsafe_action, failsafe_cause); - - mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); } } + if (action != Action::Warn) { + mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); + }; } + #endif /* EMSCRIPTEN_BUILD */ } From a9f7f00844cf2dededef6d8a04a23847aebc49ff Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 21 May 2025 14:40:46 +0200 Subject: [PATCH 021/130] batteryCheck: refine low battery reporting sevirity To make sure QGC also shows a box and reads out for "low battery" and make events and mavlink_log reports consistent. Low - Critical Critical - Critical Emergency - Emergency --- .../HealthAndArmingChecks/checks/batteryCheck.cpp | 12 ++++++------ src/modules/commander/failsafe/framework.cpp | 3 +-- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp index daba5b5006..9b40fb39ac 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/batteryCheck.cpp @@ -204,12 +204,12 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) const bool critical_or_higher = reporter.failsafeFlags().battery_warning >= battery_status_s::WARNING_CRITICAL; NavModes affected_modes = (!configured_arm_threshold_in_use && critical_or_higher) || (configured_arm_threshold_in_use && below_configured_arm_threshold) ? NavModes::All : NavModes::None; - events::LogLevel log_level = critical_or_higher || below_configured_arm_threshold - ? events::Log::Critical : events::Log::Warning; switch (reporter.failsafeFlags().battery_warning) { default: case battery_status_s::WARNING_LOW: + // This is declared critical so QGC displays a yellow box and reads "low battery" out loud making the user aware + /* EVENT * @description * The lowest battery state of charge is below the low threshold. @@ -219,10 +219,10 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) * */ reporter.armingCheckFailure(affected_modes, health_component_t::battery, events::ID("check_battery_low"), - log_level, "Low battery"); + events::Log::Critical, "Low battery"); if (reporter.mavlink_log_pub()) { - mavlink_log_warning(reporter.mavlink_log_pub(), "Low battery\t"); + mavlink_log_critical(reporter.mavlink_log_pub(), "Low battery\t"); } break; @@ -237,7 +237,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) * */ reporter.armingCheckFailure(affected_modes, health_component_t::battery, events::ID("check_battery_critical"), - log_level, "Critical battery"); + events::Log::Critical, "Critical battery"); if (reporter.mavlink_log_pub()) { mavlink_log_critical(reporter.mavlink_log_pub(), "Critical battery\t"); @@ -255,7 +255,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter) * */ reporter.armingCheckFailure(affected_modes, health_component_t::battery, events::ID("check_battery_emergency"), - log_level, "Emergency battery level"); + events::Log::Emergency, "Emergency battery level"); if (reporter.mavlink_log_pub()) { mavlink_log_emergency(reporter.mavlink_log_pub(), "Emergency battery level\t"); diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 9e5b1bc62b..3de8305702 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -292,10 +292,9 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action if (action != Action::Warn) { mavlink_log_critical(&_mavlink_log_pub, "Failsafe activated\t"); - }; + } } - #endif /* EMSCRIPTEN_BUILD */ } From cc199aa807605c9908aaa723eef3451c9af1e1fa Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Wed, 21 May 2025 12:46:56 +0200 Subject: [PATCH 022/130] [board] Disable buzzer on Skynode base boards --- boards/px4/fmu-v5x/init/rc.board_defaults | 3 +++ boards/px4/fmu-v6x/init/rc.board_defaults | 3 +++ 2 files changed, 6 insertions(+) diff --git a/boards/px4/fmu-v5x/init/rc.board_defaults b/boards/px4/fmu-v5x/init/rc.board_defaults index e0381e9886..1880b95d6a 100644 --- a/boards/px4/fmu-v5x/init/rc.board_defaults +++ b/boards/px4/fmu-v5x/init/rc.board_defaults @@ -13,6 +13,9 @@ then param set-default UXRCE_DDS_PTCFG 2 param set-default UXRCE_DDS_AG_IP 170461697 param set-default UXRCE_DDS_CFG 1000 + + # The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). + param set-default CBRK_BUZZER 782097 else # Mavlink ethernet (CFG 1000) param set-default MAV_2_CONFIG 1000 diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index bdc99a68e7..2d9a6ea49a 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -15,6 +15,9 @@ then param set-default UXRCE_DDS_PTCFG 2 param set-default UXRCE_DDS_AG_IP 170461697 param set-default UXRCE_DDS_CFG 1000 + + # The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). + param set-default CBRK_BUZZER 782097 else # Mavlink ethernet (CFG 1000) param set-default MAV_2_CONFIG 1000 From 700ad7e49fe905e3086b6694c2b493a87f96d501 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Thu, 22 May 2025 07:49:55 +1000 Subject: [PATCH 023/130] New Crowdin translations - zh-CN (#24895) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 1 + docs/zh/modules/modules_autotune.md | 8 +- docs/zh/modules/modules_command.md | 160 ++++---- docs/zh/modules/modules_communication.md | 19 +- docs/zh/modules/modules_controller.md | 83 ++-- docs/zh/modules/modules_driver.md | 373 ++++-------------- .../modules/modules_driver_airspeed_sensor.md | 28 +- docs/zh/modules/modules_driver_baro.md | 60 +-- docs/zh/modules/modules_driver_camera.md | 4 +- .../modules/modules_driver_distance_sensor.md | 92 ++--- docs/zh/modules/modules_driver_imu.md | 136 ++----- docs/zh/modules/modules_driver_ins.md | 6 +- .../zh/modules/modules_driver_magnetometer.md | 56 +-- .../zh/modules/modules_driver_optical_flow.md | 6 +- .../modules/modules_driver_radio_control.md | 122 ++++++ docs/zh/modules/modules_driver_rpm_sensor.md | 4 +- docs/zh/modules/modules_driver_transponder.md | 4 +- docs/zh/modules/modules_estimator.md | 20 +- docs/zh/modules/modules_simulation.md | 4 +- docs/zh/modules/modules_system.md | 215 ++++------ docs/zh/modules/modules_template.md | 8 +- docs/zh/sim_sih/index.md | 18 +- .../community_supported_simulators.md | 14 +- 23 files changed, 505 insertions(+), 936 deletions(-) create mode 100644 docs/zh/modules/modules_driver_radio_control.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index 12fc678e53..0321a017bc 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -739,6 +739,7 @@ - [磁罗盘](modules/modules_driver_magnetometer.md) - [光流](modules/modules_driver_optical_flow.md) - [Rpm Sensor](modules/modules_driver_rpm_sensor.md) + - [Radio Control](modules/modules_driver_radio_control.md) - [Transponder](modules/modules_driver_transponder.md) - [估计器](modules/modules_estimator.md) - [仿真](modules/modules_simulation.md) diff --git a/docs/zh/modules/modules_autotune.md b/docs/zh/modules/modules_autotune.md index cd4f484c68..da9b2bf6e7 100644 --- a/docs/zh/modules/modules_autotune.md +++ b/docs/zh/modules/modules_autotune.md @@ -6,9 +6,7 @@ Source: [modules/fw_autotune_attitude_control](https://github.com/PX4/PX4-Autopi ### 描述 - - -### 用法 +### Usage {#fw_autotune_attitude_control_usage} ``` fw_autotune_attitude_control [arguments...] @@ -27,9 +25,7 @@ Source: [modules/mc_autotune_attitude_control](https://github.com/PX4/PX4-Autopi ### 描述 - - -### 用法 +### Usage {#mc_autotune_attitude_control_usage} ``` mc_autotune_attitude_control [arguments...] diff --git a/docs/zh/modules/modules_command.md b/docs/zh/modules/modules_command.md index adeda2a371..8cb347995d 100644 --- a/docs/zh/modules/modules_command.md +++ b/docs/zh/modules/modules_command.md @@ -8,9 +8,7 @@ Source: [systemcmds/actuator_test](https://github.com/PX4/PX4-Autopilot/tree/mai 警告:在使用此命令之前移除所有螺旋桨。 - - -### 用法 +### Usage {#actuator_test_usage} ``` actuator_test [arguments...] @@ -34,9 +32,9 @@ actuator_test [arguments...] Source: [systemcmds/bl_update](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bl_update) -Utility to flash the bootloader from a file +Utility to flash the bootloader from a file -### 用法 +### Usage {#bl_update_usage} ``` bl_update [arguments...] @@ -50,9 +48,9 @@ bl_update [arguments...] Source: [systemcmds/bsondump](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bsondump) -Utility to read BSON from a file and print or output document size. +Utility to read BSON from a file and print or output document size. -### 用法 +### Usage {#bsondump_usage} ``` bsondump [arguments...] @@ -63,9 +61,9 @@ bsondump [arguments...] Source: [systemcmds/dumpfile](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dumpfile) -转储文件实用程序。 以二进制模式(不要用 CR LF 替换 LF)将文件大小和内容打印到标准输出。 +Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. -### 用法 +### Usage {#dumpfile_usage} ``` dumpfile [arguments...] @@ -78,7 +76,7 @@ Source: [systemcmds/dyn](https://github.com/PX4/PX4-Autopilot/tree/main/src/syst ### 描述 -加载并运行一个没有被编译进 PX4 的二进制文件的动态 PX4 模块 +Load and run a dynamic PX4 module, which was not compiled into the PX4 binary. ### Example @@ -86,9 +84,7 @@ Source: [systemcmds/dyn](https://github.com/PX4/PX4-Autopilot/tree/main/src/syst dyn ./hello.px4mod start ``` - - -### 用法 +### Usage {#dyn_usage} ``` dyn [arguments...] @@ -102,21 +98,19 @@ Source: [systemcmds/failure](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### 描述 -向系统中注入故障。 +Inject failures into system. ### 实现 -此系统命令通过 uORB 发送一个机体命令来出发故障。 +This system command sends a vehicle command over uORB to trigger failure. ### 示例 -通过停止GPS来测试GPS故障保护: +Test the GPS failsafe by stopping GPS: failure gps off - - -### 用法 +### Usage {#failure_usage} ``` failure [arguments...] @@ -135,7 +129,7 @@ Source: [systemcmds/gpio](https://github.com/PX4/PX4-Autopilot/tree/main/src/sys ### 描述 -此命令用于读写GPIO +This command is used to read and write GPIOs ``` gpio read / [PULLDOWN|PULLUP] [--force] @@ -144,7 +138,7 @@ gpio write / [PUSHPULL|OPENDRAIN] [--force] ### 示例 -读取配置为上拉的 PH4 引脚,它的值为高 +Read the value on port H pin 4 configured as pullup, and it is high ``` gpio read H4 PULLUP @@ -152,7 +146,7 @@ gpio read H4 PULLUP 1 OK -设置 PE7 的输出值为高 +Set the output value on Port E pin 7 to high ``` gpio write E7 1 --force @@ -164,9 +158,7 @@ Set the output value on device /dev/gpio1 to high gpio write /dev/gpio1 1 ``` - - -### 用法 +### Usage {#gpio_usage} ``` gpio [arguments...] @@ -186,13 +178,11 @@ gpio [arguments...] Source: [systemcmds/hardfault_log](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hardfault_log) -Hardfault 实用程序 +Hardfault utility -在启动脚本中用于处理 hardfaults。 +Used in startup scripts to handle hardfaults - - -### 用法 +### Usage {#hardfault_log_usage} ``` hardfault_log [arguments...] @@ -219,9 +209,9 @@ hardfault_log [arguments...] Source: [systemcmds/hist](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hist) -Command-line tool to show the px4 message history. There are no arguments. +Command-line tool to show the px4 message history. There are no arguments. -### 用法 +### Usage {#hist_usage} ``` hist [arguments...] @@ -231,9 +221,9 @@ hist [arguments...] Source: [systemcmds/i2cdetect](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/i2cdetect) -Utility to scan for I2C devices on a particular bus. +Utility to scan for I2C devices on a particular bus. -### 用法 +### Usage {#i2cdetect_usage} ``` i2cdetect [arguments...] @@ -249,21 +239,21 @@ Source: [systemcmds/led_control](https://github.com/PX4/PX4-Autopilot/tree/main/ Command-line tool to control & test the (external) LED's. -要使用它,请确保有一个处理 led_control 的 uorb 主题的设备正在运行。 +To use it make sure there's a driver running, which handles the led_control uorb topic. -有不同的优先级,例如一个模块可以设置低优先级的颜色,另一个模块可以高优先级闪烁 N 次,闪烁后 LED 自动返回低优先级状态。 The `reset` command can also be used to return to a lower priority. +There are different priorities, such that for example one module can set a color with low priority, and another +module can blink N times with high priority, and the LED's automatically return to the lower priority state +after the blinking. The `reset` command can also be used to return to a lower priority. ### 示例 -第一个 LED 闪烁蓝光 5 次: +Blink the first LED 5 times in blue: ``` led_control blink -c blue -l 0 -n 5 ``` - - -### 用法 +### Usage {#led_control_usage} ``` led_control [arguments...] @@ -299,13 +289,11 @@ led_control [arguments...] Source: [systemcmds/topic_listener](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/topic_listener) -监听 uORB 主题并将数据打印到控制台的实用程序。 +Utility to listen on uORB topics and print the data to the console. -可以通过按 Ctrl+C、Esc 或 Q 随时退出侦听器。 +The listener can be exited any time by pressing Ctrl+C, Esc, or Q. - - -### 用法 +### Usage {#listener_usage} ``` listener [arguments...] @@ -323,9 +311,9 @@ listener [arguments...] Source: [systemcmds/mft](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft) -Utility interact with the manifest +Utility interact with the manifest -### 用法 +### Usage {#mfd_usage} ``` mfd [arguments...] @@ -337,9 +325,9 @@ mfd [arguments...] Source: [systemcmds/mft_cfg](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft_cfg) -Tool to set and get manifest configuration +Tool to set and get manifest configuration -### 用法 +### Usage {#mft_cfg_usage} ``` mft_cfg [arguments...] @@ -358,9 +346,9 @@ mft_cfg [arguments...] Source: [systemcmds/mtd](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mtd) -Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) +Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) -### 用法 +### Usage {#mtd_usage} ``` mtd [arguments...] @@ -386,14 +374,12 @@ mtd [arguments...] Source: [systemcmds/nshterm](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/nshterm) -在指定端口启动一个 NSH shell。 +Start an NSH shell on a given port. -该命令此前被用于在 USB 串口端口开启一个 shell。 -现在运行mavlink,并且可以在mavlink 上使用shell。 +This was previously used to start a shell on the USB serial port. +Now there runs mavlink, and it is possible to use a shell over mavlink. - - -### 用法 +### Usage {#nshterm_usage} ``` nshterm [arguments...] @@ -406,22 +392,24 @@ Source: [systemcmds/param](https://github.com/PX4/PX4-Autopilot/tree/main/src/sy ### 描述 -通过 shell 或脚本访问和操作参数的命令。 +Command to access and manipulate parameters via shell or script. -例如,这在启动脚本中用于设置特定于机身的参数。 +This is used for example in the startup script to set airframe-specific parameters. -Parameters are automatically saved when changed, eg. with `param set`. 它们通常存储在 FRAM 或 SD 卡中。 `param select` can be used to change the storage location for subsequent saves (this will +Parameters are automatically saved when changed, eg. with `param set`. They are typically stored to FRAM +or to the SD card. `param select` can be used to change the storage location for subsequent saves (this will need to be (re-)configured on every boot). If the FLASH-based backend is enabled (which is done at compile time, e.g. for the Intel Aero or Omnibus), `param select` has no effect and the default is always the FLASH backend. However `param save/load ` can still be used to write to/read from files. -每个参数有一个“已使用”的标志,此标志在启动过程参数被读取后被置位。 它只是用于向地面控制站显示相关参数。 +Each parameter has a 'used' flag, which is set when it's read during boot. It is used to only show relevant +parameters to a ground control station. ### 示例 -更改机身并确保已加载机身的默认参数: +Change the airframe and make sure the airframe's default parameters are loaded: ``` param set SYS_AUTOSTART 4001 @@ -429,9 +417,7 @@ param set SYS_AUTOCONFIG 1 reboot ``` - - -### 用法 +### Usage {#param_usage} ``` param [arguments...] @@ -509,9 +495,7 @@ Source: [modules/payload_deliverer](https://github.com/PX4/PX4-Autopilot/tree/ma Handles payload delivery with either Gripper or a Winch with an appropriate timeout / feedback sensor setting, and communicates back the delivery result as an acknowledgement internally - - -### 用法 +### Usage {#payload_deliverer_usage} ``` payload_deliverer [arguments...] @@ -533,9 +517,9 @@ payload_deliverer [arguments...] Source: [systemcmds/perf](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/perf) -Tool to print performance counters +Tool to print performance counters -### 用法 +### Usage {#perf_usage} ``` perf [arguments...] @@ -550,9 +534,9 @@ perf [arguments...] Source: [systemcmds/reboot](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/reboot) -Reboot the system +Reboot the system -### 用法 +### Usage {#reboot_usage} ``` reboot [arguments...] @@ -565,9 +549,9 @@ reboot [arguments...] Source: [systemcmds/sd_bench](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_bench) -Test the speed of an SD Card +Test the speed of an SD Card -### 用法 +### Usage {#sd_bench_usage} ``` sd_bench [arguments...] @@ -588,9 +572,9 @@ sd_bench [arguments...] Source: [systemcmds/sd_stress](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_stress) -Test operations on an SD Card +Test operations on an SD Card -### 用法 +### Usage {#sd_stress_usage} ``` sd_stress [arguments...] @@ -604,13 +588,11 @@ sd_stress [arguments...] Source: [systemcmds/serial_passthru](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/serial_passthru) -把数据从一个设备传输到另一个设备。 +Pass data from one device to another. This can be used to use u-center connected to USB with a GPS on a serial port. - - -### 用法 +### Usage {#serial_passthru_usage} ``` serial_passthru [arguments...] @@ -623,7 +605,7 @@ serial_passthru [arguments...] [-t] Track the External devices baudrate on internal device ``` -## 系统时间 +## system_time Source: [systemcmds/system_time](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/system_time) @@ -640,9 +622,7 @@ system_time set 1600775044 system_time get ``` - - -### 用法 +### Usage {#system_time_usage} ``` system_time [arguments...] @@ -656,9 +636,9 @@ system_time [arguments...] Source: [systemcmds/top](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/top) -Monitor running processes and their CPU, stack usage, priority and state +Monitor running processes and their CPU, stack usage, priority and state -### 用法 +### Usage {#top_usage} ``` top [arguments...] @@ -670,9 +650,9 @@ top [arguments...] Source: [systemcmds/usb_connected](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/usb_connected) Utility to check if USB is connected. Was previously used in startup scripts. -A return value of 0 means USB is connected, 1 otherwise. +A return value of 0 means USB is connected, 1 otherwise. -### 用法 +### Usage {#usb_connected_usage} ``` usb_connected [arguments...] @@ -682,9 +662,9 @@ usb_connected [arguments...] Source: [systemcmds/ver](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/ver) -Tool to print various version information +Tool to print various version information -### 用法 +### Usage {#ver_usage} ``` ver [arguments...] diff --git a/docs/zh/modules/modules_communication.md b/docs/zh/modules/modules_communication.md index 995d0f9d31..d5f172e79a 100644 --- a/docs/zh/modules/modules_communication.md +++ b/docs/zh/modules/modules_communication.md @@ -4,9 +4,9 @@ Source: [drivers/telemetry/frsky_telemetry](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/frsky_telemetry) -FrSky 数传支持, FrSky Telemetry support. Auto-detects D or S.PORT protocol. +FrSky 数传支持, FrSky Telemetry support. Auto-detects D or S.PORT protocol. -### 用法 +### Usage {#frsky_telemetry_usage} ``` frsky_telemetry [arguments...] @@ -64,9 +64,7 @@ mavlink start -u 14556 -r 1000000 mavlink stream -u 14556 -s HIGHRES_IMU -r 50 ``` - - -### 用法 +### Usage {#mavlink_usage} ``` mavlink [arguments...] @@ -129,7 +127,7 @@ Source: [systemcmds/uorb](https://github.com/PX4/PX4-Autopilot/tree/main/src/sys ### 描述 -uORB 是各模块之间进行通讯的基于 发布-订阅 机制的内部消息传递系统。 +uORB is the internal pub-sub messaging system, used for communication between modules. ### 实现 @@ -140,19 +138,18 @@ The code is optimized to minimize the memory footprint and the latency to exchan Messages are defined in the `/msg` directory. They are converted into C/C++ code at build-time. -该接口基于文件描述符(file descriptor)实现:它在内部使用 readwriteioctl。 The interface is based on file descriptors: internally it uses read, write and ioctl. Except for the publications, which use orb_advert_t handles, so that they can be used from interrupts as well (on NuttX). +If compiled with ORB_USE_PUBLISHER_RULES, a file with uORB publication rules can be used to configure which +modules are allowed to publish which topics. This is used for system-wide replay. ### 示例 -Messages are defined in the /msg directory. They are converted into C/C++ code at build-time. Besides `top`, this is an important command for general system inspection: +Monitor topic publication rates. Besides `top`, this is an important command for general system inspection: ``` uorb top ``` - - -### 用法 +### Usage {#uorb_usage} ``` uorb [arguments...] diff --git a/docs/zh/modules/modules_controller.md b/docs/zh/modules/modules_controller.md index a3bf296295..68d8bdd25f 100644 --- a/docs/zh/modules/modules_controller.md +++ b/docs/zh/modules/modules_controller.md @@ -16,9 +16,7 @@ Currently it is feeding the `manual_control_setpoint` topic directly to the actu To reduce control latency, the module directly polls on the gyro topic published by the IMU driver. - - -### 用法 +### Usage {#airship_att_control_usage} ``` airship_att_control [arguments...] @@ -39,9 +37,7 @@ Source: [modules/control_allocator](https://github.com/PX4/PX4-Autopilot/tree/ma This implements control allocation. It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages. - - -### 用法 +### Usage {#control_allocator_usage} ``` control_allocator [arguments...] @@ -53,7 +49,7 @@ control_allocator [arguments...] status print status info ``` -## fw_pos_control_l1 +## flight_mode_manager Source: [modules/flight_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/flight_mode_manager) @@ -62,9 +58,7 @@ Source: [modules/flight_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/ This implements the setpoint generation for all modes. It takes the current mode state of the vehicle as input and outputs setpoints for controllers. - - -### 用法 +### Usage {#flight_mode_manager_usage} ``` flight_mode_manager [arguments...] @@ -76,7 +70,7 @@ flight_mode_manager [arguments...] status print status info ``` -## mc_att_control +## fw_att_control Source: [modules/fw_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_att_control) @@ -84,9 +78,7 @@ Source: [modules/fw_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/ fw_att_control is the fixed wing attitude controller. - - -### 用法 +### Usage {#fw_att_control_usage} ``` fw_att_control [arguments...] @@ -107,9 +99,7 @@ Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/ fw_pos_control is the fixed-wing position controller. - - -### 用法 +### Usage {#fw_pos_control_usage} ``` fw_pos_control [arguments...] @@ -130,9 +120,7 @@ Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main fw_rate_control is the fixed-wing rate controller. - - -### 用法 +### Usage {#fw_rate_control_usage} ``` fw_rate_control [arguments...] @@ -156,13 +144,14 @@ setpoints (`vehicle_attitude_setpoint`) as inputs and outputs a rate setpoint. The controller has a P loop for angular error -The different internal modes are implemented as separate classes that inherit from a common base class NavigatorMode. The member _navigation_mode contains the current active mode. +Publication documenting the implemented Quaternion Attitude Control: +Nonlinear Quadrocopter Attitude Control (2013) +by Dario Brescianini, Markus Hehn and Raffaello D'Andrea +Institute for Dynamic Systems and Control (IDSC), ETH Zurich https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf - - -### 用法 +### Usage {#mc_att_control_usage} ``` mc_att_control [arguments...] @@ -175,7 +164,7 @@ mc_att_control [arguments...] status print status info ``` -## navigator +## mc_pos_control Source: [modules/mc_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_pos_control) @@ -188,9 +177,7 @@ Output of the velocity controller is thrust vector that is split to thrust direc The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and logging. - - -### 用法 +### Usage {#mc_pos_control_usage} ``` mc_pos_control [arguments...] @@ -214,9 +201,7 @@ via `manual_control_setpoint` topic) as inputs and outputs actuator control mess The controller has a PID loop for angular rate error. - - -### 用法 +### Usage {#mc_rate_control_usage} ``` mc_rate_control [arguments...] @@ -247,9 +232,7 @@ The member `_navigation_mode` contains the current active mode. Navigator publishes position setpoint triplets (`position_setpoint_triplet_s`), which are then used by the position controller. - - -### 用法 +### Usage {#navigator_usage} ``` navigator [arguments...] @@ -273,9 +256,7 @@ Source: [modules/rover_ackermann](https://github.com/PX4/PX4-Autopilot/tree/main Rover ackermann module. - - -### 用法 +### Usage {#rover_ackermann_usage} ``` rover_ackermann [arguments...] @@ -295,9 +276,7 @@ Source: [modules/rover_differential](https://github.com/PX4/PX4-Autopilot/tree/m Rover differential module. - - -### 用法 +### Usage {#rover_differential_usage} ``` rover_differential [arguments...] @@ -317,9 +296,7 @@ Source: [modules/rover_mecanum](https://github.com/PX4/PX4-Autopilot/tree/main/s Rover mecanum module. - - -### 用法 +### Usage {#rover_mecanum_usage} ``` rover_mecanum [arguments...] @@ -359,9 +336,7 @@ rover_pos_control status rover_pos_control stop ``` - - -### 用法 +### Usage {#rover_pos_control_usage} ``` rover_pos_control [arguments...] @@ -384,9 +359,7 @@ It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages. ``` - - -### 用法 +### Usage {#spacecraft_usage} ``` spacecraft [arguments...] @@ -425,9 +398,7 @@ uuv_att_control status uuv_att_control stop ``` - - -### 用法 +### Usage {#uuv_att_control_usage} ``` uuv_att_control [arguments...] @@ -465,9 +436,7 @@ uuv_pos_control status uuv_pos_control stop ``` - - -### 用法 +### Usage {#uuv_pos_control_usage} ``` uuv_pos_control [arguments...] @@ -487,9 +456,7 @@ Source: [modules/vtol_att_control](https://github.com/PX4/PX4-Autopilot/tree/mai fw_att_control is the fixed wing attitude controller. - - -### 用法 +### Usage {#vtol_att_control_usage} ``` vtol_att_control [arguments...] diff --git a/docs/zh/modules/modules_driver.md b/docs/zh/modules/modules_driver.md index 1c4620794d..ae19d698dc 100644 --- a/docs/zh/modules/modules_driver.md +++ b/docs/zh/modules/modules_driver.md @@ -3,23 +3,22 @@ 子分类 - [Airspeed Sensor](modules_driver_airspeed_sensor.md) -- [Transponder](modules_driver_transponder.md) -- [Imu](modules_driver_imu.md) -- [Rpm Sensor](modules_driver_rpm_sensor.md) -- [Magnetometer](modules_driver_magnetometer.md) +- [Baro](modules_driver_baro.md) - [Camera](modules_driver_camera.md) - [Distance Sensor](modules_driver_distance_sensor.md) -- [Optical Flow](modules_driver_optical_flow.md) +- [Imu](modules_driver_imu.md) - [Ins](modules_driver_ins.md) -- [Baro](modules_driver_baro.md) +- [Magnetometer](modules_driver_magnetometer.md) +- [Optical Flow](modules_driver_optical_flow.md) +- [Radio Control](modules_driver_radio_control.md) +- [Rpm Sensor](modules_driver_rpm_sensor.md) +- [Transponder](modules_driver_transponder.md) ## MCP23009 Source: [drivers/gpio/mcp23009](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gpio/mcp23009) - - -### 用法 +### Usage {#MCP23009_usage} ``` MCP23009 [arguments...] @@ -53,11 +52,9 @@ Source: [drivers/adc/board_adc](https://github.com/PX4/PX4-Autopilot/tree/main/s ### 描述 -ADC 驱动。 +ADC driver. - - -### 用法 +### Usage {#adc_usage} ``` adc [arguments...] @@ -89,9 +86,7 @@ It is enabled/disabled using the parameter, and is disabled by default. If enabled, internal ADCs are not used. - - -### 用法 +### Usage {#ads1115_usage} ``` ads1115 [arguments...] @@ -117,13 +112,11 @@ Source: [drivers/osd/atxxxx](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### 描述 -例如挂载在OmnibusF4SD板上的针对 ATXXXX 芯片的OSD驱动。 +OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example. -可以通过 OSD_ATXXXX_CFG 参数使能. +It can be enabled with the OSD_ATXXXX_CFG parameter. - - -### 用法 +### Usage {#atxxxx_usage} ``` atxxxx [arguments...] @@ -149,19 +142,18 @@ Source: [drivers/smart_battery/batmon](https://github.com/PX4/PX4-Autopilot/tree ### 描述 -用于智能电池的BQ40Z50电量统计芯片 +Driver for SMBUS Communication with BatMon enabled smart-battery +Setup/usage information: https://rotoye.com/batmon-tutorial/ ### 示例 To start at address 0x0B, on bus 4 ``` -batt_smbus -X write_flash 19069 2 27 0 +batmon start -X -a 11 -b 4 ``` - - -### 用法 +### Usage {#batmon_usage} ``` batmon [arguments...] @@ -193,7 +185,7 @@ Source: [drivers/batt_smbus](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### 描述 -This will enable capturing on the 4th pin. Then do: +Smart battery driver for the BQ40Z50 fuel gauge IC. ### 示例 @@ -203,9 +195,7 @@ To write to flash to set parameters. address, number_of_bytes, byte0, ... , byte batt_smbus -X write_flash 19069 2 27 0 ``` - - -### 用法 +### Usage {#batt_smbus_usage} ``` batt_smbus [arguments...] @@ -246,9 +236,7 @@ batt_smbus [arguments...] Source: [drivers/telemetry/bst](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/bst) - - -### 用法 +### Usage {#bst_usage} ``` bst [arguments...] @@ -268,31 +256,7 @@ bst [arguments...] status print status info ``` -## crsf_rc - -Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) - -### 描述 - -This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data - - - -### 用法 - -``` -crsf_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - -## sf1xx +## dshot Source: [drivers/dshot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/dshot) @@ -307,8 +271,8 @@ It skips all pins already in use (e.g. by a camera trigger module). It supports: - DShot150, DShot300, DShot600 -- 通过独立的串口遥控,并且发布esc_status消息 -- 通过命令行接口发送 DShot 命令 +- telemetry via separate UART and publishing as esc_status message +- sending DShot commands via CLI ### 示例 @@ -321,9 +285,7 @@ dshot save -m 1 After saving, the reversed direction will be regarded as the normal one. So to reverse again repeat the same commands. - - -### 用法 +### Usage {#dshot_usage} ``` dshot [arguments...] @@ -371,41 +333,13 @@ dshot [arguments...] status print status info ``` -## dsm_rc - -Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) - -### 描述 - -This module does Spektrum DSM RC input parsing. - - - -### 用法 - -``` -dsm_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` - -## fmu mode_pwm +## fake_gps Source: [examples/fake_gps](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/fake_gps) ### 描述 - - -### 用法 +### Usage {#fake_gps_usage} ``` fake_gps [arguments...] @@ -423,9 +357,7 @@ Source: [examples/fake_imu](https://github.com/PX4/PX4-Autopilot/tree/main/src/e ### 描述 - - -### 用法 +### Usage {#fake_imu_usage} ``` fake_imu [arguments...] @@ -437,7 +369,7 @@ fake_imu [arguments...] status print status info ``` -## gps +## fake_magnetometer Source: [examples/fake_magnetometer](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/fake_magnetometer) @@ -446,9 +378,7 @@ Source: [examples/fake_magnetometer](https://github.com/PX4/PX4-Autopilot/tree/m Publish the earth magnetic field as a fake magnetometer (sensor_mag). Requires vehicle_attitude and vehicle_gps_position. - - -### 用法 +### Usage {#fake_magnetometer_usage} ``` fake_magnetometer [arguments...] @@ -479,15 +409,13 @@ Attempt to start driver on a specified serial device. ft_technologies_serial start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` ft_technologies_serial stop ``` - - -### 用法 +### Usage {#ft_technologies_serial_usage} ``` ft_technologies_serial [arguments...] @@ -498,30 +426,6 @@ ft_technologies_serial [arguments...] stop Stop driver ``` -## ghst_rc - -Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) - -### 描述 - -This module does Ghost (GHST) RC input parsing. - - - -### 用法 - -``` -ghst_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## gimbal Source: [modules/gimbal](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/gimbal) @@ -541,9 +445,7 @@ Test the output by setting a angles (all omitted axes are set to 0): gimbal test pitch -45 yaw 30 ``` - - -### 用法 +### Usage {#gimbal_usage} ``` gimbal [arguments...] @@ -598,9 +500,7 @@ Initiate warm restart of GPS device gps reset warm ``` - - -### 用法 +### Usage {#gps_usage} ``` gps [arguments...] @@ -635,9 +535,7 @@ Source: [modules/simulation/gz_bridge](https://github.com/PX4/PX4-Autopilot/tree ### 描述 - - -### 用法 +### Usage {#gz_bridge_usage} ``` gz_bridge [arguments...] @@ -668,9 +566,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 用法 +### Usage {#ina220_usage} ``` ina220 [arguments...] @@ -712,9 +608,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 用法 +### Usage {#ina226_usage} ``` ina226 [arguments...] @@ -754,9 +648,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 用法 +### Usage {#ina228_usage} ``` ina228 [arguments...] @@ -796,9 +688,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 用法 +### Usage {#ina238_usage} ``` ina238 [arguments...] @@ -831,9 +721,7 @@ IridiumSBD driver. Creates a virtual serial port that another module can use for communication (e.g. mavlink). - - -### 用法 +### Usage {#iridiumsbd_usage} ``` iridiumsbd [arguments...] @@ -855,9 +743,7 @@ iridiumsbd [arguments...] Source: [drivers/irlock](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/irlock) - - -### 用法 +### Usage {#irlock_usage} ``` irlock [arguments...] @@ -885,9 +771,7 @@ Source: [drivers/linux_pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main/s Linux PWM output driver with board-specific backend implementation. - - -### 用法 +### Usage {#linux_pwm_out_usage} ``` linux_pwm_out [arguments...] @@ -903,9 +787,7 @@ linux_pwm_out [arguments...] Source: [drivers/magnetometer/lsm303agr](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm303agr) - - -### 用法 +### Usage {#lsm303agr_usage} ``` lsm303agr [arguments...] @@ -947,9 +829,7 @@ CLI usage example: msp_osd ``` - - -### 用法 +### Usage {#msp_osd_usage} ``` msp_osd [arguments...] @@ -977,9 +857,7 @@ neopixel -n 8 To drive all available leds. - - -### 用法 +### Usage {#newpixel_usage} ``` newpixel [arguments...] @@ -993,9 +871,7 @@ newpixel [arguments...] Source: [drivers/optical_flow/paa3905](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paa3905) - - -### 用法 +### Usage {#paa3905_usage} ``` paa3905 [arguments...] @@ -1021,9 +897,7 @@ paa3905 [arguments...] Source: [drivers/optical_flow/paw3902](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paw3902) - - -### 用法 +### Usage {#paw3902_usage} ``` paw3902 [arguments...] @@ -1067,9 +941,7 @@ It is typically started with: pca9685_pwm_out start -a 0x40 -b 1 ``` - - -### 用法 +### Usage {#pca9685_pwm_out_usage} ``` pca9685_pwm_out [arguments...] @@ -1093,9 +965,7 @@ Source: [drivers/power_monitor/pm_selector_auterion](https://github.com/PX4/PX4- Driver for starting and auto-detecting different power monitors. - - -### 用法 +### Usage {#pm_selector_auterion_usage} ``` pm_selector_auterion [arguments...] @@ -1111,9 +981,7 @@ pm_selector_auterion [arguments...] Source: [drivers/optical_flow/pmw3901](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/pmw3901) - - -### 用法 +### Usage {#pmw3901_usage} ``` pmw3901 [arguments...] @@ -1143,9 +1011,7 @@ Source: [drivers/pps_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src This implements capturing PPS information from the GNSS module and calculates the drift between PPS and Real-time clock. - - -### 用法 +### Usage {#pps_capture_usage} ``` pps_capture [arguments...] @@ -1167,9 +1033,7 @@ This module is responsible for driving the output pins. For boards without a sep (eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the px4io driver is used for main ones. - - -### 用法 +### Usage {#pwm_out_usage} ``` pwm_out [arguments...] @@ -1195,9 +1059,7 @@ mix them with any loaded mixer and output the result to the It is used in SITL and HITL. - - -### 用法 +### Usage {#pwm_out_sim_usage} ``` pwm_out_sim [arguments...] @@ -1215,9 +1077,7 @@ pwm_out_sim [arguments...] Source: [drivers/optical_flow/px4flow](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/px4flow) - - -### 用法 +### Usage {#px4flow_usage} ``` px4flow [arguments...] @@ -1245,9 +1105,7 @@ Source: [drivers/px4io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drive Output driver communicating with the IO co-processor. - - -### 用法 +### Usage {#px4io_usage} ``` px4io [arguments...] @@ -1281,46 +1139,11 @@ px4io [arguments...] status print status info ``` -## rc_input - -Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) - -### 描述 - -This module does the RC input parsing and auto-selecting the method. Supported methods are: - -- PPM -- SBUS -- DSM -- SUMD -- ST24 -- TBS Crossfire (CRSF) - - - -### 用法 - -``` -rc_input [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` - ## rgbled Source: [drivers/lights/rgbled_ncp5623c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_ncp5623c) - - -### 用法 +### Usage {#rgbled_usage} ``` rgbled [arguments...] @@ -1346,9 +1169,7 @@ rgbled [arguments...] Source: [drivers/lights/rgbled_is31fl3195](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_is31fl3195) - - -### 用法 +### Usage {#rgbled_is31fl3195_usage} ``` rgbled_is31fl3195 [arguments...] @@ -1384,9 +1205,7 @@ This used in some GPS modules by Holybro for [PX4 status notification](../gettin The driver is included by default in firmware (KConfig key DRIVERS_LIGHTS_RGBLED_LP5562) and is always enabled. - - -### 用法 +### Usage {#rgbled_lp5562_usage} ``` rgbled_lp5562 [arguments...] @@ -1427,9 +1246,7 @@ the address `RBCLW_ADDRESS` needs to match the ESC configuration. The command to start this driver is: `$ roboclaw start ` - - -### 用法 +### Usage {#roboclaw_usage} ``` roboclaw [arguments...] @@ -1445,9 +1262,7 @@ roboclaw [arguments...] Source: [drivers/rpm_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm_capture) - - -### 用法 +### Usage {#rpm_capture_usage} ``` rpm_capture [arguments...] @@ -1468,9 +1283,7 @@ Source: [drivers/safety_button](https://github.com/PX4/PX4-Autopilot/tree/main/s This module is responsible for the safety button. Pressing the safety button 3 times quickly will trigger a GCS pairing request. - - -### 用法 +### Usage {#safety_button_usage} ``` safety_button [arguments...] @@ -1482,30 +1295,6 @@ safety_button [arguments...] status print status info ``` -## sbus_rc - -Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) - -### 描述 - -This module does SBUS RC input parsing. - - - -### 用法 - -``` -sbus_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## septentrio Source: [drivers/gnss/septentrio](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gnss/septentrio) @@ -1539,9 +1328,7 @@ Perform warm reset of the receivers: gps reset warm ``` - - -### 用法 +### Usage {#septentrio_usage} ``` septentrio [arguments...] @@ -1600,9 +1387,7 @@ sht3x reset Reinitialize senzor, reset flags - - -### 用法 +### Usage {#sht3x_usage} ``` sht3x [arguments...] @@ -1649,9 +1434,7 @@ The module is typically started with: tap_esc start -d /dev/ttyS2 -n <1-8> ``` - - -### 用法 +### Usage {#tap_esc_usage} ``` tap_esc [arguments...] @@ -1671,9 +1454,7 @@ Source: [drivers/tone_alarm](https://github.com/PX4/PX4-Autopilot/tree/main/src/ This module is responsible for the tone alarm. - - -### 用法 +### Usage {#tone_alarm_usage} ``` tone_alarm [arguments...] @@ -1702,9 +1483,7 @@ Start the driver with a given device: uwb start -d /dev/ttyS2 ``` - - -### 用法 +### Usage {#uwb_usage} ``` uwb [arguments...] @@ -1724,9 +1503,7 @@ uwb [arguments...] Source: [drivers/actuators/vertiq_io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/actuators/vertiq_io) - - -### 用法 +### Usage {#vertiq_io_usage} ``` vertiq_io [arguments...] @@ -1749,9 +1526,7 @@ This module is responsible for driving the output pins. For boards without a sep (eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the px4io driver is used for main ones. - - -### 用法 +### Usage {#voxl2_io_usage} ``` voxl2_io [arguments...] @@ -1791,9 +1566,7 @@ It is typically started with: todo ``` - - -### 用法 +### Usage {#voxl_esc_usage} ``` voxl_esc [arguments...] @@ -1840,9 +1613,7 @@ voxl_esc [arguments...] Source: [drivers/power_monitor/voxlpm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/voxlpm) - - -### 用法 +### Usage {#voxlpm_usage} ``` voxlpm [arguments...] @@ -1872,9 +1643,7 @@ Source: [modules/zenoh](https://github.com/PX4/PX4-Autopilot/tree/main/src/modul Zenoh demo bridge - - -### 用法 +### Usage {#zenoh_usage} ``` zenoh [arguments...] diff --git a/docs/zh/modules/modules_driver_airspeed_sensor.md b/docs/zh/modules/modules_driver_airspeed_sensor.md index 2f58f9b086..09a55cec1a 100644 --- a/docs/zh/modules/modules_driver_airspeed_sensor.md +++ b/docs/zh/modules/modules_driver_airspeed_sensor.md @@ -13,9 +13,7 @@ This is not included by default in firmware. It can be included with terminal co or in default.px4board with adding the line: "CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y" It can be enabled with the "SENS_EN_ASP5033" parameter set to 1. - - -### 用法 +### Usage {#asp5033_usage} ``` asp5033 [arguments...] @@ -39,9 +37,7 @@ asp5033 [arguments...] Source: [drivers/differential_pressure/auav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/auav) - - -### 用法 +### Usage {#auav_usage} ``` auav [arguments...] @@ -67,9 +63,7 @@ auav [arguments...] Source: [drivers/differential_pressure/ets](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ets) - - -### 用法 +### Usage {#ets_airspeed_usage} ``` ets_airspeed [arguments...] @@ -93,9 +87,7 @@ ets_airspeed [arguments...] Source: [drivers/differential_pressure/ms4515](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4515) - - -### 用法 +### Usage {#ms4515_usage} ``` ms4515 [arguments...] @@ -119,9 +111,7 @@ ms4515 [arguments...] Source: [drivers/differential_pressure/ms4525do](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4525do) - - -### 用法 +### Usage {#ms4525do_usage} ``` ms4525do [arguments...] @@ -145,9 +135,7 @@ ms4525do [arguments...] Source: [drivers/differential_pressure/ms5525dso](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms5525dso) - - -### 用法 +### Usage {#ms5525dso_usage} ``` ms5525dso [arguments...] @@ -171,9 +159,7 @@ ms5525dso [arguments...] Source: [drivers/differential_pressure/sdp3x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/sdp3x) - - -### 用法 +### Usage {#sdp3x_usage} ``` sdp3x [arguments...] diff --git a/docs/zh/modules/modules_driver_baro.md b/docs/zh/modules/modules_driver_baro.md index 0b6676f98f..be32c800ed 100644 --- a/docs/zh/modules/modules_driver_baro.md +++ b/docs/zh/modules/modules_driver_baro.md @@ -4,9 +4,7 @@ Source: [drivers/barometer/bmp280](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp280) - - -### 用法 +### Usage {#bmp280_usage} ``` bmp280 [arguments...] @@ -42,9 +40,7 @@ bmp280 [arguments...] Source: [drivers/barometer/bmp388](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp388) - - -### 用法 +### Usage {#bmp388_usage} ``` bmp388 [arguments...] @@ -72,9 +68,7 @@ bmp388 [arguments...] Source: [drivers/barometer/bmp581](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp581) - - -### 用法 +### Usage {#bmp581_usage} ``` bmp581 [arguments...] @@ -102,9 +96,7 @@ bmp581 [arguments...] Source: [drivers/barometer/dps310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/dps310) - - -### 用法 +### Usage {#dps310_usage} ``` dps310 [arguments...] @@ -140,9 +132,7 @@ dps310 [arguments...] Source: [drivers/barometer/invensense/icp101xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp101xx) - - -### 用法 +### Usage {#icp101xx_usage} ``` icp101xx [arguments...] @@ -166,9 +156,7 @@ icp101xx [arguments...] Source: [drivers/barometer/invensense/icp201xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp201xx) - - -### 用法 +### Usage {#icp201xx_usage} ``` icp201xx [arguments...] @@ -192,9 +180,7 @@ icp201xx [arguments...] Source: [drivers/barometer/lps22hb](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps22hb) - - -### 用法 +### Usage {#lps22hb_usage} ``` lps22hb [arguments...] @@ -220,9 +206,7 @@ lps22hb [arguments...] Source: [drivers/barometer/lps25h](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps25h) - - -### 用法 +### Usage {#lps25h_usage} ``` lps25h [arguments...] @@ -248,9 +232,7 @@ lps25h [arguments...] Source: [drivers/barometer/lps33hw](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps33hw) - - -### 用法 +### Usage {#lps33hw_usage} ``` lps33hw [arguments...] @@ -279,9 +261,7 @@ lps33hw [arguments...] Source: [drivers/barometer/maiertek/mpc2520](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/maiertek/mpc2520) - - -### 用法 +### Usage {#mpc2520_usage} ``` mpc2520 [arguments...] @@ -305,9 +285,7 @@ mpc2520 [arguments...] Source: [drivers/barometer/mpl3115a2](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/mpl3115a2) - - -### 用法 +### Usage {#mpl3115a2_usage} ``` mpl3115a2 [arguments...] @@ -331,9 +309,7 @@ mpl3115a2 [arguments...] Source: [drivers/barometer/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - - -### 用法 +### Usage {#ms5611_usage} ``` ms5611 [arguments...] @@ -369,9 +345,7 @@ ms5611 [arguments...] Source: [drivers/barometer/ms5837](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5837) - - -### 用法 +### Usage {#ms5837_usage} ``` ms5837 [arguments...] @@ -393,9 +367,7 @@ ms5837 [arguments...] Source: [drivers/barometer/goertek/spa06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spa06) - - -### 用法 +### Usage {#spa06_usage} ``` spa06 [arguments...] @@ -431,9 +403,7 @@ spa06 [arguments...] Source: [drivers/barometer/goertek/spl06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spl06) - - -### 用法 +### Usage {#spl06_usage} ``` spl06 [arguments...] diff --git a/docs/zh/modules/modules_driver_camera.md b/docs/zh/modules/modules_driver_camera.md index 55e355dc0c..60881d33e0 100644 --- a/docs/zh/modules/modules_driver_camera.md +++ b/docs/zh/modules/modules_driver_camera.md @@ -34,9 +34,7 @@ In particular: [Setup/usage information](../camera/index.md). - - -### 用法 +### Usage {#camera_trigger_usage} ``` camera_trigger [arguments...] diff --git a/docs/zh/modules/modules_driver_distance_sensor.md b/docs/zh/modules/modules_driver_distance_sensor.md index 76d7ac38a1..649c1ca6b7 100644 --- a/docs/zh/modules/modules_driver_distance_sensor.md +++ b/docs/zh/modules/modules_driver_distance_sensor.md @@ -16,15 +16,13 @@ Attempt to start driver on a specified serial device. afbrs50 start ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` afbrs50 stop ``` - - -### 用法 +### Usage {#afbrs50_usage} ``` afbrs50 [arguments...] @@ -43,9 +41,7 @@ afbrs50 [arguments...] Source: [drivers/distance_sensor/gy_us42](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/gy_us42) - - -### 用法 +### Usage {#gy_us42_usage} ``` gy_us42 [arguments...] @@ -73,7 +69,7 @@ Source: [drivers/distance_sensor/leddar_one](https://github.com/PX4/PX4-Autopilo Serial bus driver for the LeddarOne LiDAR. -针对 Lightware SFxx 系列 LIDAR 测距仪的 I2C 总线驱动: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20。 +Most boards are configured to enable/start the driver on a specified UART using the SENS_LEDDAR1_CFG parameter. Setup/usage information: https://docs.px4.io/main/en/sensor/leddar_one.html @@ -85,15 +81,13 @@ Attempt to start driver on a specified serial device. leddar_one start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` leddar_one stop ``` - - -### 用法 +### Usage {#leddar_one_usage} ``` leddar_one [arguments...] @@ -112,13 +106,11 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### 描述 -设置/使用 信息: https://docs.px4.io/master/en/sensor/sfxx_lidar.html +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html - - -### 用法 +### Usage {#lightware_laser_i2c_usage} ``` lightware_laser_i2c [arguments...] @@ -160,15 +152,13 @@ Attempt to start driver on a specified serial device. lightware_laser_serial start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` lightware_laser_serial stop ``` - - -### 用法 +### Usage {#lightware_laser_serial_usage} ``` lightware_laser_serial [arguments...] @@ -197,15 +187,13 @@ Attempt to start driver on a specified serial device. lightware_sf45_serial start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` lightware_sf45_serial stop ``` - - -### 用法 +### Usage {#lightware_sf45_serial_usage} ``` lightware_sf45_serial [arguments...] @@ -224,13 +212,11 @@ Source: [drivers/distance_sensor/ll40ls_pwm](https://github.com/PX4/PX4-Autopilo PWM driver for LidarLite rangefinders. -超声笔测距仪驱动,负责处理与设备的用心并通过 uORB 将距离信息发布出去。 +The sensor/driver must be enabled using the parameter SENS_EN_LL40LS. Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html - - -### 用法 +### Usage {#ll40ls_usage} ``` ll40ls [arguments...] @@ -244,13 +230,11 @@ ll40ls [arguments...] stop Stop driver ``` -## pga460 +## mappydot Source: [drivers/distance_sensor/mappydot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mappydot) - - -### 用法 +### Usage {#mappydot_usage} ``` mappydot [arguments...] @@ -272,9 +256,7 @@ mappydot [arguments...] Source: [drivers/distance_sensor/mb12xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mb12xx) - - -### 用法 +### Usage {#mb12xx_usage} ``` mb12xx [arguments...] @@ -312,9 +294,7 @@ running. A simple algorithm to detect false readings is implemented at the drive the quality of data that is being published. The driver will not publish data at all if it deems the sensor data to be invalid or unstable. - - -### 用法 +### Usage {#pga460_usage} ``` pga460 [arguments...] @@ -333,9 +313,7 @@ pga460 [arguments...] Source: [drivers/distance_sensor/srf02](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/srf02) - - -### 用法 +### Usage {#srf02_usage} ``` srf02 [arguments...] @@ -367,9 +345,7 @@ Driver for HY-SRF05 / HC-SR05 and HC-SR04 rangefinders. The sensor/driver must be enabled using the parameter SENS_EN_HXSRX0X. - - -### 用法 +### Usage {#srf05_usage} ``` srf05 [arguments...] @@ -399,9 +375,7 @@ The sensor/driver must be enabled using the parameter SENS_EN_TRANGER. Setup/usage information: https://docs.px4.io/main/en/sensor/rangefinders.html#teraranger-rangefinders - - -### 用法 +### Usage {#teraranger_usage} ``` teraranger [arguments...] @@ -427,9 +401,7 @@ teraranger [arguments...] Source: [drivers/distance_sensor/tf02pro](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/tf02pro) - - -### 用法 +### Usage {#tf02pro_usage} ``` tf02pro [arguments...] @@ -471,15 +443,13 @@ Attempt to start driver on a specified serial device. tfmini start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` tfmini stop ``` - - -### 用法 +### Usage {#tfmini_usage} ``` tfmini [arguments...] @@ -514,15 +484,13 @@ Attempt to start driver on a specified serial device. ulanding_radar start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` ulanding_radar stop ``` - - -### 用法 +### Usage {#ulanding_radar_usage} ``` ulanding_radar [arguments...] @@ -540,9 +508,7 @@ ulanding_radar [arguments...] Source: [drivers/distance_sensor/vl53l0x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l0x) - - -### 用法 +### Usage {#vl53l0x_usage} ``` vl53l0x [arguments...] @@ -568,9 +534,7 @@ vl53l0x [arguments...] Source: [drivers/distance_sensor/vl53l1x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l1x) - - -### 用法 +### Usage {#vl53l1x_usage} ``` vl53l1x [arguments...] diff --git a/docs/zh/modules/modules_driver_imu.md b/docs/zh/modules/modules_driver_imu.md index 98f8f7c98d..67f9a2713b 100644 --- a/docs/zh/modules/modules_driver_imu.md +++ b/docs/zh/modules/modules_driver_imu.md @@ -4,9 +4,7 @@ Source: [drivers/imu/analog_devices/adis16448](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16448) - - -### 用法 +### Usage {#adis16448_usage} ``` adis16448 [arguments...] @@ -32,9 +30,7 @@ adis16448 [arguments...] Source: [drivers/imu/analog_devices/adis16470](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16470) - - -### 用法 +### Usage {#adis16470_usage} ``` adis16470 [arguments...] @@ -60,9 +56,7 @@ adis16470 [arguments...] Source: [drivers/imu/analog_devices/adis16477](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16477) - - -### 用法 +### Usage {#adis16477_usage} ``` adis16477 [arguments...] @@ -88,9 +82,7 @@ adis16477 [arguments...] Source: [drivers/imu/analog_devices/adis16497](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16497) - - -### 用法 +### Usage {#adis16497_usage} ``` adis16497 [arguments...] @@ -116,9 +108,7 @@ adis16497 [arguments...] Source: [drivers/imu/analog_devices/adis16507](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16507) - - -### 用法 +### Usage {#adis16507_usage} ``` adis16507 [arguments...] @@ -144,9 +134,7 @@ adis16507 [arguments...] Source: [drivers/imu/bosch/bmi055](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi055) - - -### 用法 +### Usage {#bmi055_usage} ``` bmi055 [arguments...] @@ -174,9 +162,7 @@ bmi055 [arguments...] Source: [drivers/imu/bosch/bmi085](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi085) - - -### 用法 +### Usage {#bmi085_usage} ``` bmi085 [arguments...] @@ -204,9 +190,7 @@ bmi085 [arguments...] Source: [drivers/imu/bosch/bmi088](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088) - - -### 用法 +### Usage {#bmi088_usage} ``` bmi088 [arguments...] @@ -234,9 +218,7 @@ bmi088 [arguments...] Source: [drivers/imu/bosch/bmi088_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088_i2c) - - -### 用法 +### Usage {#bmi088_i2c_usage} ``` bmi088_i2c [arguments...] @@ -264,9 +246,7 @@ bmi088_i2c [arguments...] Source: [drivers/imu/bosch/bmi270](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi270) - - -### 用法 +### Usage {#bmi270_usage} ``` bmi270 [arguments...] @@ -292,9 +272,7 @@ bmi270 [arguments...] Source: [drivers/imu/nxp/fxas21002c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxas21002c) - - -### 用法 +### Usage {#fxas21002c_usage} ``` fxas21002c [arguments...] @@ -328,9 +306,7 @@ fxas21002c [arguments...] Source: [drivers/imu/nxp/fxos8701cq](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxos8701cq) - - -### 用法 +### Usage {#fxos8701cq_usage} ``` fxos8701cq [arguments...] @@ -364,9 +340,7 @@ fxos8701cq [arguments...] Source: [drivers/imu/invensense/iam20680hp](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iam20680hp) - - -### 用法 +### Usage {#iam20680hp_usage} ``` iam20680hp [arguments...] @@ -392,9 +366,7 @@ iam20680hp [arguments...] Source: [drivers/imu/invensense/icm20602](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20602) - - -### 用法 +### Usage {#icm20602_usage} ``` icm20602 [arguments...] @@ -420,9 +392,7 @@ icm20602 [arguments...] Source: [drivers/imu/invensense/icm20608g](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20608g) - - -### 用法 +### Usage {#icm20608g_usage} ``` icm20608g [arguments...] @@ -448,9 +418,7 @@ icm20608g [arguments...] Source: [drivers/imu/invensense/icm20649](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20649) - - -### 用法 +### Usage {#icm20649_usage} ``` icm20649 [arguments...] @@ -476,9 +444,7 @@ icm20649 [arguments...] Source: [drivers/imu/invensense/icm20689](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20689) - - -### 用法 +### Usage {#icm20689_usage} ``` icm20689 [arguments...] @@ -504,9 +470,7 @@ icm20689 [arguments...] Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - - -### 用法 +### Usage {#icm20948_usage} ``` icm20948 [arguments...] @@ -533,9 +497,7 @@ icm20948 [arguments...] Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - - -### 用法 +### Usage {#icm20948_i2c_passthrough_usage} ``` icm20948_i2c_passthrough [arguments...] @@ -559,9 +521,7 @@ icm20948_i2c_passthrough [arguments...] Source: [drivers/imu/invensense/icm40609d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm40609d) - - -### 用法 +### Usage {#icm40609d_usage} ``` icm40609d [arguments...] @@ -587,9 +547,7 @@ icm40609d [arguments...] Source: [drivers/imu/invensense/icm42605](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42605) - - -### 用法 +### Usage {#icm42605_usage} ``` icm42605 [arguments...] @@ -615,9 +573,7 @@ icm42605 [arguments...] Source: [drivers/imu/invensense/icm42670p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42670p) - - -### 用法 +### Usage {#icm42670p_usage} ``` icm42670p [arguments...] @@ -643,9 +599,7 @@ icm42670p [arguments...] Source: [drivers/imu/invensense/icm42688p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42688p) - - -### 用法 +### Usage {#icm42688p_usage} ``` icm42688p [arguments...] @@ -674,9 +628,7 @@ icm42688p [arguments...] Source: [drivers/imu/invensense/icm45686](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm45686) - - -### 用法 +### Usage {#icm45686_usage} ``` icm45686 [arguments...] @@ -704,9 +656,7 @@ icm45686 [arguments...] Source: [drivers/imu/invensense/iim42652](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42652) - - -### 用法 +### Usage {#iim42652_usage} ``` iim42652 [arguments...] @@ -734,9 +684,7 @@ iim42652 [arguments...] Source: [drivers/imu/invensense/iim42653](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42653) - - -### 用法 +### Usage {#iim42653_usage} ``` iim42653 [arguments...] @@ -764,9 +712,7 @@ iim42653 [arguments...] Source: [drivers/imu/st/l3gd20](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/l3gd20) - - -### 用法 +### Usage {#l3gd20_usage} ``` l3gd20 [arguments...] @@ -796,9 +742,7 @@ l3gd20 [arguments...] Source: [drivers/imu/st/lsm303d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm303d) - - -### 用法 +### Usage {#lsm303d_usage} ``` lsm303d [arguments...] @@ -824,9 +768,7 @@ lsm303d [arguments...] Source: [drivers/imu/st/lsm9ds1](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm9ds1) - - -### 用法 +### Usage {#lsm9ds1_usage} ``` lsm9ds1 [arguments...] @@ -852,9 +794,7 @@ lsm9ds1 [arguments...] Source: [drivers/imu/invensense/mpu6000](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6000) - - -### 用法 +### Usage {#mpu6000_usage} ``` mpu6000 [arguments...] @@ -880,9 +820,7 @@ mpu6000 [arguments...] Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - - -### 用法 +### Usage {#mpu9250_usage} ``` mpu9250 [arguments...] @@ -909,9 +847,7 @@ mpu9250 [arguments...] Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - - -### 用法 +### Usage {#mpu9250_i2c_usage} ``` mpu9250_i2c [arguments...] @@ -937,9 +873,7 @@ mpu9250_i2c [arguments...] Source: [drivers/imu/invensense/mpu6500](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6500) - - -### 用法 +### Usage {#mpu9520_usage} ``` mpu9520 [arguments...] @@ -965,9 +899,7 @@ mpu9520 [arguments...] Source: [drivers/imu/murata/sch16t](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/murata/sch16t) - - -### 用法 +### Usage {#sch16t_usage} ``` sch16t [arguments...] diff --git a/docs/zh/modules/modules_driver_ins.md b/docs/zh/modules/modules_driver_ins.md index b1b7e13526..e469f2bfbc 100644 --- a/docs/zh/modules/modules_driver_ins.md +++ b/docs/zh/modules/modules_driver_ins.md @@ -20,15 +20,13 @@ Attempt to start driver on a specified serial device. vectornav start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` vectornav stop ``` - - -### 用法 +### Usage {#vectornav_usage} ``` vectornav [arguments...] diff --git a/docs/zh/modules/modules_driver_magnetometer.md b/docs/zh/modules/modules_driver_magnetometer.md index b009ed86ee..8d527cfa4e 100644 --- a/docs/zh/modules/modules_driver_magnetometer.md +++ b/docs/zh/modules/modules_driver_magnetometer.md @@ -4,9 +4,7 @@ Source: [drivers/magnetometer/akm/ak09916](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak09916) - - -### 用法 +### Usage {#ak09916_usage} ``` ak09916 [arguments...] @@ -32,9 +30,7 @@ ak09916 [arguments...] Source: [drivers/magnetometer/akm/ak8963](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak8963) - - -### 用法 +### Usage {#ak8963_usage} ``` ak8963 [arguments...] @@ -60,9 +56,7 @@ ak8963 [arguments...] Source: [drivers/magnetometer/bosch/bmm150](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm150) - - -### 用法 +### Usage {#bmm150_usage} ``` bmm150 [arguments...] @@ -88,9 +82,7 @@ bmm150 [arguments...] Source: [drivers/magnetometer/bosch/bmm350](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm350) - - -### 用法 +### Usage {#bmm350_usage} ``` bmm350 [arguments...] @@ -116,9 +108,7 @@ bmm350 [arguments...] Source: [drivers/magnetometer/hmc5883](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/hmc5883) - - -### 用法 +### Usage {#hmc5883_usage} ``` hmc5883 [arguments...] @@ -147,9 +137,7 @@ hmc5883 [arguments...] Source: [drivers/magnetometer/st/iis2mdc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/st/iis2mdc) - - -### 用法 +### Usage {#iis2mdc_usage} ``` iis2mdc [arguments...] @@ -173,9 +161,7 @@ iis2mdc [arguments...] Source: [drivers/magnetometer/isentek/ist8308](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8308) - - -### 用法 +### Usage {#ist8308_usage} ``` ist8308 [arguments...] @@ -201,9 +187,7 @@ ist8308 [arguments...] Source: [drivers/magnetometer/isentek/ist8310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8310) - - -### 用法 +### Usage {#ist8310_usage} ``` ist8310 [arguments...] @@ -229,9 +213,7 @@ ist8310 [arguments...] Source: [drivers/magnetometer/lis3mdl](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lis3mdl) - - -### 用法 +### Usage {#lis3mdl_usage} ``` lis3mdl [arguments...] @@ -263,9 +245,7 @@ lis3mdl [arguments...] Source: [drivers/magnetometer/lsm9ds1_mag](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm9ds1_mag) - - -### 用法 +### Usage {#lsm9ds1_mag_usage} ``` lsm9ds1_mag [arguments...] @@ -291,9 +271,7 @@ lsm9ds1_mag [arguments...] Source: [drivers/magnetometer/memsic/mmc5983ma](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/memsic/mmc5983ma) - - -### 用法 +### Usage {#mmc5983ma_usage} ``` mmc5983ma [arguments...] @@ -325,9 +303,7 @@ mmc5983ma [arguments...] Source: [drivers/magnetometer/qmc5883l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/qmc5883l) - - -### 用法 +### Usage {#qmc5883l_usage} ``` qmc5883l [arguments...] @@ -353,9 +329,7 @@ qmc5883l [arguments...] Source: [drivers/magnetometer/rm3100](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/rm3100) - - -### 用法 +### Usage {#rm3100_usage} ``` rm3100 [arguments...] @@ -383,9 +357,7 @@ rm3100 [arguments...] Source: [drivers/magnetometer/vtrantech/vcm1193l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/vtrantech/vcm1193l) - - -### 用法 +### Usage {#vcm1193l_usage} ``` vcm1193l [arguments...] diff --git a/docs/zh/modules/modules_driver_optical_flow.md b/docs/zh/modules/modules_driver_optical_flow.md index f646f49540..097660a8e3 100644 --- a/docs/zh/modules/modules_driver_optical_flow.md +++ b/docs/zh/modules/modules_driver_optical_flow.md @@ -20,15 +20,13 @@ Attempt to start driver on a specified serial device. thoneflow start -d /dev/ttyS1 ``` -设置/使用 信息: https://docs.px4.io/master/en/sensor/leddar_one.html +Stop driver ``` thoneflow stop ``` - - -### 用法 +### Usage {#thoneflow_usage} ``` thoneflow [arguments...] diff --git a/docs/zh/modules/modules_driver_radio_control.md b/docs/zh/modules/modules_driver_radio_control.md new file mode 100644 index 0000000000..e49199d3ec --- /dev/null +++ b/docs/zh/modules/modules_driver_radio_control.md @@ -0,0 +1,122 @@ +# Modules Reference: Radio Control (Driver) + +## crsf_rc + +Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) + +### 描述 + +This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data + +### Usage {#crsf_rc_usage} + +``` +crsf_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## dsm_rc + +Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) + +### 描述 + +This module does Spektrum DSM RC input parsing. + +### Usage {#dsm_rc_usage} + +``` +dsm_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## ghst_rc + +Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) + +### 描述 + +This module does Ghost (GHST) RC input parsing. + +### Usage {#ghst_rc_usage} + +``` +ghst_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## rc_input + +Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) + +### 描述 + +This module does the RC input parsing and auto-selecting the method. Supported methods are: + +- PPM +- SBUS +- DSM +- SUMD +- ST24 +- TBS Crossfire (CRSF) + +### Usage {#rc_input_usage} + +``` +rc_input [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## sbus_rc + +Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) + +### 描述 + +This module does SBUS RC input parsing. + +### Usage {#sbus_rc_usage} + +``` +sbus_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` diff --git a/docs/zh/modules/modules_driver_rpm_sensor.md b/docs/zh/modules/modules_driver_rpm_sensor.md index fd96c85ef0..b4d7b95243 100644 --- a/docs/zh/modules/modules_driver_rpm_sensor.md +++ b/docs/zh/modules/modules_driver_rpm_sensor.md @@ -4,9 +4,7 @@ Source: [drivers/rpm/pcf8583](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm/pcf8583) - - -### 用法 +### Usage {#pcf8583_usage} ``` pcf8583 [arguments...] diff --git a/docs/zh/modules/modules_driver_transponder.md b/docs/zh/modules/modules_driver_transponder.md index 9076c6def2..cd9e77ee03 100644 --- a/docs/zh/modules/modules_driver_transponder.md +++ b/docs/zh/modules/modules_driver_transponder.md @@ -24,9 +24,7 @@ Set the Squawk Code $ sagetech_mxs squawk 1200 ``` - - -### 用法 +### Usage {#sagetech_mxs_usage} ``` sagetech_mxs [arguments...] diff --git a/docs/zh/modules/modules_estimator.md b/docs/zh/modules/modules_estimator.md index f7b2f45db0..10f1bbac29 100644 --- a/docs/zh/modules/modules_estimator.md +++ b/docs/zh/modules/modules_estimator.md @@ -8,9 +8,7 @@ Source: [modules/attitude_estimator_q](https://github.com/PX4/PX4-Autopilot/tree Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing. - - -### 用法 +### Usage {#AttitudeEstimatorQ_usage} ``` AttitudeEstimatorQ [arguments...] @@ -36,9 +34,7 @@ to a valid sensor in case of failure detection. For failure detection as well as the estimation of a scale factor from IAS to CAS, it runs several wind estimators and also publishes those. - - -### 用法 +### Usage {#airspeed_estimator_usage} ``` airspeed_estimator [arguments...] @@ -63,9 +59,7 @@ The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.p ekf2 can be started in replay mode (`-r`): in this mode, it does not access the system time, but only uses the timestamps from the sensor topics. - - -### 用法 +### Usage {#ekf2_usage} ``` ekf2 [arguments...] @@ -90,9 +84,7 @@ Source: [modules/local_position_estimator](https://github.com/PX4/PX4-Autopilot/ 基于扩展卡尔曼滤波器的姿态和位置估计器。 - - -### 用法 +### Usage {#local_position_estimator_usage} ``` local_position_estimator [arguments...] @@ -110,9 +102,7 @@ Source: [modules/mc_hover_thrust_estimator](https://github.com/PX4/PX4-Autopilot ### 描述 - - -### 用法 +### Usage {#mc_hover_thrust_estimator_usage} ``` mc_hover_thrust_estimator [arguments...] diff --git a/docs/zh/modules/modules_simulation.md b/docs/zh/modules/modules_simulation.md index 775a46c055..6051db28c3 100644 --- a/docs/zh/modules/modules_simulation.md +++ b/docs/zh/modules/modules_simulation.md @@ -21,9 +21,7 @@ signals given by the control allocation module. 积分计算采用前向欧拉法。 为避免堆栈溢出,大部分变量在 .hpp 文件中声明为全局变量。 - - -### 用法 +### Usage {#simulator_sih_usage} ``` simulator_sih [arguments...] diff --git a/docs/zh/modules/modules_system.md b/docs/zh/modules/modules_system.md index ef8b780bfc..3d3f6b2905 100644 --- a/docs/zh/modules/modules_system.md +++ b/docs/zh/modules/modules_system.md @@ -6,9 +6,7 @@ Source: [modules/simulation/battery_simulator](https://github.com/PX4/PX4-Autopi ### 描述 - - -### 用法 +### Usage {#battery_simulator_usage} ``` battery_simulator [arguments...] @@ -26,17 +24,15 @@ Source: [modules/battery_status](https://github.com/PX4/PX4-Autopilot/tree/main/ ### 描述 -模块提供的功能包括: +The provided functionality includes: - Read the output from the ADC driver (via ioctl interface) and publish `battery_status`. ### 实现 -模块运行在它自己的线程中,并轮询当前选定的陀螺仪主题。 +It runs in its own thread and polls on the currently selected gyro topic. - - -### 用法 +### Usage {#battery_status_usage} ``` battery_status [arguments...] @@ -74,9 +70,7 @@ It discards topics from the `camera_trigger` module if camera capture is enabled For the topics that are not discarded it creates a `CameraCapture` topic with the timestamp information from the `CameraTrigger` and position information from the vehicle. - - -### 用法 +### Usage {#camera_feedback_usage} ``` camera_feedback [arguments...] @@ -99,9 +93,7 @@ The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin and continue to check for VBUS and start mavlink once it is detected. - - -### 用法 +### Usage {#cdcacm_autostart_usage} ``` cdcacm_autostart [arguments...] @@ -119,11 +111,9 @@ Source: [modules/commander](https://github.com/PX4/PX4-Autopilot/tree/main/src/m ### 描述 -该模块包含飞行模式切换和失效保护状态机。 +The commander module contains the state machine for mode switching and failsafe behavior. - - -### 用法 +### Usage {#commander_usage} ``` commander [arguments...] @@ -177,22 +167,20 @@ Source: [modules/dataman](https://github.com/PX4/PX4-Autopilot/tree/main/src/mod ### 描述 -该模块通过基于C语言的API以简单数据库的形式为系统的其他部分提供持续性存储功能。 +Module to provide persistent storage for the rest of the system in form of a simple database through a C API. Multiple backends are supported depending on the board: - a file (eg. on the SD card) -- FLASH(需要飞控板支持) +- RAM (this is obviously not persistent) -It is used to store structured data of different types: mission waypoints, mission state and geofence polygons. Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible. -每种类型的数据都有一个特定的类型和一个固定的最大存储条目的数量,因此可以实现对数据的快速随机访问。 +It is used to store structured data of different types: mission waypoints, mission state and geofence polygons. +Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible. ### 实现 -单个数据的读取和写入是原子操作。 +Reading and writing a single item is always atomic. - - -### 用法 +### Usage {#dataman_usage} ``` dataman [arguments...] @@ -216,20 +204,18 @@ Source: [systemcmds/dmesg](https://github.com/PX4/PX4-Autopilot/tree/main/src/sy ### 描述 -用于显示启动控制台消息的命令行工具 -需要注意的是,NuttX系统的工作队列和系统日志输出都未被捕捉到。 +Command-line tool to show bootup console messages. +Note that output from NuttX's work queues and syslog are not captured. ### 示例 -持续在后台打印所有消息。 +Keep printing all messages in the background: ``` dmesg -f & ``` - - -### 用法 +### Usage {#dmesg_usage} ``` dmesg [arguments...] @@ -243,11 +229,9 @@ Source: [modules/esc_battery](https://github.com/PX4/PX4-Autopilot/tree/main/src ### 描述 -Background process running periodically with 1 Hz on the LP work queue to calculate the CPU load and RAM usage and publish the cpuload topic. +This implements using information from the ESC status and publish it as battery status. - - -### 用法 +### Usage {#esc_battery_usage} ``` esc_battery [arguments...] @@ -265,11 +249,9 @@ Source: [modules/gyro_calibration](https://github.com/PX4/PX4-Autopilot/tree/mai ### 描述 -源码:drivers/heater +Simple online gyroscope calibration. - - -### 用法 +### Usage {#gyro_calibration_usage} ``` gyro_calibration [arguments...] @@ -281,15 +263,13 @@ gyro_calibration [arguments...] status print status info ``` -## heater +## gyro_fft Source: [modules/gyro_fft](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/gyro_fft) ### 描述 - - -### 用法 +### Usage {#gyro_fft_usage} ``` gyro_fft [arguments...] @@ -301,19 +281,17 @@ gyro_fft [arguments...] status print status info ``` -## land_detector +## heater Source: [drivers/heater](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/heater) ### 描述 -源码:modules/land_detector +Background process running periodically on the LP work queue to regulate IMU temperature at a setpoint. This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI. - - -### 用法 +### Usage {#heater_usage} ``` heater [arguments...] @@ -333,9 +311,7 @@ Source: [systemcmds/i2c_launcher](https://github.com/PX4/PX4-Autopilot/tree/main Daemon that starts drivers based on found I2C devices. - - -### 用法 +### Usage {#i2c_launcher_usage} ``` i2c_launcher [arguments...] @@ -401,9 +377,7 @@ The architecture is as shown below: - - -### 用法 +### Usage {#internal_combustion_engine_control_usage} ``` internal_combustion_engine_control [arguments...] @@ -415,7 +389,7 @@ internal_combustion_engine_control [arguments...] status print status info ``` -## load_mon +## land_detector Source: [modules/land_detector](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/land_detector) @@ -427,10 +401,11 @@ states, such as commanded thrust, arming state and vehicle motion. ### 实现 -Every type is implemented in its own class with a common base class. 触发时间由变量 MAYBE_LAND_TRIGGER_TIME 定义。 当检测到 maybe_landed 状态时,位置控制器会将推理设定值设置为零。 A hysteresis and a fixed +Every type is implemented in its own class with a common base class. The base class maintains a state (landed, +maybe_landed, ground_contact). Each possible state is implemented in the derived classes. A hysteresis and a fixed priority of each internal state determines the actual land_detector state. -#### 多旋翼的 Land Detector +#### Multicopter Land Detector **ground_contact**: thrust setpoint and velocity in z-direction must be below a defined threshold for time GROUND_CONTACT_TRIGGER_TIME_US. When ground_contact is detected, the position controller turns off the thrust setpoint @@ -442,11 +417,9 @@ position controller sets the thrust setpoint to zero. **landed**: it requires maybe_landed to be true for time LAND_DETECTOR_TRIGGER_TIME_US. -There are 2 environment variables used for configuration: replay, which must be set to an ULog file name - it's the log file to be replayed. The second is the mode, specified via replay_mode: +The module runs periodically on the HP work queue. - - -### 用法 +### Usage {#land_detector_usage} ``` land_detector [arguments...] @@ -459,7 +432,7 @@ land_detector [arguments...] status print status info ``` -## logger +## load_mon Source: [modules/load_mon](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/load_mon) @@ -471,9 +444,7 @@ usage and publish the `cpuload` topic. On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output, which will also appear in the log file. - - -### 用法 +### Usage {#load_mon_usage} ``` load_mon [arguments...] @@ -497,21 +468,23 @@ tuning, replay and crash analysis. It supports 2 backends: -- 文件:写入 ULog 文件到文件系统中(SD 卡) -- MAVLink: 通过 MAVLink 将 ULog 数据流传输到客户端上(需要客户端支持此方式) +- Files: write ULog files to the file system (SD card) +- MAVLink: stream ULog data via MAVLink to a client (the client must support this) -模块的实现使用了两个线程: +Both backends can be enabled and used at the same time. -In between there is a write buffer with configurable size (and another fixed-size buffer for the mission log). It should be large to avoid dropouts. 缓冲区应大到可以避免出现数据溢出。 It can be enabled and configured via SDLOG_MISSION parameter. +The file backend supports 2 types of log files: full (the normal log) and a mission +log. The mission log is a reduced ulog file and can be used for example for geotagging or +vehicle management. It can be enabled and configured via SDLOG_MISSION parameter. The normal log is always a superset of the mission log. ### 实现 -立刻开始记录日志的典型用法: +The implementation uses two threads: - The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for data updates -- 写入线程,将数据写入文件中、 +- The writer thread, writing data to the file In between there is a write buffer with configurable size (and another fixed-size buffer for the mission log). It should be large to avoid dropouts. @@ -521,7 +494,7 @@ the mission log). It should be large to avoid dropouts. Typical usage to start logging immediately: ``` -logger on +logger start -e -t ``` Or if already running: @@ -530,9 +503,7 @@ Or if already running: logger on ``` - - -### 用法 +### Usage {#logger_usage} ``` logger [arguments...] @@ -575,9 +546,7 @@ Source: [modules/mag_bias_estimator](https://github.com/PX4/PX4-Autopilot/tree/m Online magnetometer bias estimator. - - -### 用法 +### Usage {#mag_bias_estimator_usage} ``` mag_bias_estimator [arguments...] @@ -589,7 +558,7 @@ mag_bias_estimator [arguments...] status print status info ``` -## replay +## manual_control Source: [modules/manual_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/manual_control) @@ -597,9 +566,7 @@ Source: [modules/manual_control](https://github.com/PX4/PX4-Autopilot/tree/main/ Module consuming manual_control_inputs publishing one manual_control_setpoint. - - -### 用法 +### Usage {#manual_control_usage} ``` manual_control [arguments...] @@ -647,9 +614,7 @@ $ netman save # Save the parameters to the SD card. $ netman show # display current settings. $ netman update -i eth0 # do an update - - -### 用法 +### Usage {#netman_usage} ``` netman [arguments...] @@ -672,9 +637,7 @@ Source: [drivers/pwm_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/d Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input\` message. - - -### 用法 +### Usage {#pwm_input_usage} ``` pwm_input [arguments...] @@ -700,9 +663,7 @@ and then publish as `rc_channels` and `manual_control_input`. To reduce control latency, the module is scheduled on input_rc publications. - - -### 用法 +### Usage {#rc_update_usage} ``` rc_update [arguments...] @@ -737,9 +698,7 @@ the log. The replay procedure is documented on the [System-wide Replay](https://docs.px4.io/main/en/debug/system_wide_replay.html) page. - - -### 用法 +### Usage {#replay_usage} ``` replay [arguments...] @@ -766,9 +725,7 @@ It is currently only responsible for tone alarm on RC Loss. The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.). - - -### 用法 +### Usage {#send_event_usage} ``` send_event [arguments...] @@ -788,9 +745,7 @@ Source: [modules/simulation/sensor_agp_sim](https://github.com/PX4/PX4-Autopilot Module to simulate auxiliary global position measurements with optional failure modes for SIH simulation. - - -### 用法 +### Usage {#sensor_agp_sim_usage} ``` sensor_agp_sim [arguments...] @@ -808,9 +763,7 @@ Source: [modules/simulation/sensor_airspeed_sim](https://github.com/PX4/PX4-Auto ### 描述 - - -### 用法 +### Usage {#sensor_arispeed_sim_usage} ``` sensor_arispeed_sim [arguments...] @@ -828,9 +781,7 @@ Source: [modules/simulation/sensor_baro_sim](https://github.com/PX4/PX4-Autopilo ### 描述 - - -### 用法 +### Usage {#sensor_baro_sim_usage} ``` sensor_baro_sim [arguments...] @@ -848,9 +799,7 @@ Source: [modules/simulation/sensor_gps_sim](https://github.com/PX4/PX4-Autopilot ### 描述 - - -### 用法 +### Usage {#sensor_gps_sim_usage} ``` sensor_gps_sim [arguments...] @@ -868,9 +817,7 @@ Source: [modules/simulation/sensor_mag_sim](https://github.com/PX4/PX4-Autopilot ### 描述 - - -### 用法 +### Usage {#sensor_mag_sim_usage} ``` sensor_mag_sim [arguments...] @@ -891,24 +838,22 @@ Source: [modules/sensors](https://github.com/PX4/PX4-Autopilot/tree/main/src/mod The sensors module is central to the whole system. It takes low-level output from drivers, turns it into a more usable form, and publishes it for the rest of the system. -模块提供的功能包括: +The provided functionality includes: - Read the output from the sensor drivers (`SensorGyro`, etc.). - 如果存在多个同类型传感器,那个模块将进行投票和容错处理。 - 然后应用飞控板的旋转和温度校正(如果被启用)。 And finally publish the data; one of the + If there are multiple of the same type, do voting and failover handling. + Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the topics is `SensorCombined`, used by many parts of the system. - Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or - on startup. 传感器驱动使用 ioctl 接口获取参数更新。 For this to work properly, the + on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the sensor drivers must already be running when `sensors` is started. - Do sensor consistency checks and publish the `SensorsStatusImu` topic. ### 实现 -模块运行在它自己的线程中,并轮询当前选定的陀螺仪主题。 +It runs in its own thread and polls on the currently selected gyro topic. - - -### 用法 +### Usage {#sensors_usage} ``` sensors [arguments...] @@ -927,9 +872,7 @@ Source: [modules/simulation/system_power_simulator](https://github.com/PX4/PX4-A ### 描述 - - -### 用法 +### Usage {#system_power_simulation_usage} ``` system_power_simulation [arguments...] @@ -949,9 +892,7 @@ Source: [drivers/tattu_can](https://github.com/PX4/PX4-Autopilot/tree/main/src/d Driver for reading data from the Tattu 12S 16000mAh smart battery. - - -### 用法 +### Usage {#tattu_can_usage} ``` tattu_can [arguments...] @@ -975,9 +916,7 @@ whenever a change in temperature is detected. The module can also be configured routine at next boot, which allows the thermal calibration coeffecients to be calculated while the vehicle undergoes a temperature cycle. - - -### 用法 +### Usage {#temperature_compensation_usage} ``` temperature_compensation [arguments...] @@ -1007,9 +946,7 @@ Writes the RTC time cyclically to a file and reloads this value on startup. This allows monotonic time on systems that only have a software RTC (that is not battery powered). Explicitly setting the time backwards (e.g. via system_time) is still possible. - - -### 用法 +### Usage {#time_persistor_usage} ``` time_persistor [arguments...] @@ -1043,9 +980,7 @@ Play system tune #2: tune_control play -t 2 ``` - - -### 用法 +### Usage {#tune_control_usage} ``` tune_control [arguments...] @@ -1081,9 +1016,7 @@ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600 uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555 ``` - - -### 用法 +### Usage {#uxrce_dds_client_usage} ``` uxrce_dds_client [arguments...] @@ -1114,9 +1047,7 @@ Source: [systemcmds/work_queue](https://github.com/PX4/PX4-Autopilot/tree/main/s Command-line tool to show work queue status. - - -### 用法 +### Usage {#work_queue_usage} ``` work_queue [arguments...] diff --git a/docs/zh/modules/modules_template.md b/docs/zh/modules/modules_template.md index 702da90c94..77fdcf216c 100644 --- a/docs/zh/modules/modules_template.md +++ b/docs/zh/modules/modules_template.md @@ -22,9 +22,7 @@ CLI usage example: module start -f -p 42 ``` - - -### 用法 +### Usage {#module_usage} ``` module [arguments...] @@ -47,9 +45,7 @@ Source: [examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/ Example of a simple module running out of a work queue. - - -### 用法 +### Usage {#work_item_example_usage} ``` work_item_example [arguments...] diff --git a/docs/zh/sim_sih/index.md b/docs/zh/sim_sih/index.md index 2b4deb037a..473bbfcd95 100644 --- a/docs/zh/sim_sih/index.md +++ b/docs/zh/sim_sih/index.md @@ -58,6 +58,7 @@ To set up/start SIH: 2. Open QGroundControl and wait for the flight controller too boot and connect. 3. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame: - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) + - SIH Hexacopter X currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently. - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) @@ -116,25 +117,31 @@ To run SIH as SITL: 1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md). 2. Run the appropriate make command for each vehicle type (at the root of the PX4-Autopilot repository): - - quadrotor: + - Quadcopter ```sh make px4_sitl sihsim_quadx ``` - - Fixed-wing (plane): + - Hexacopter + + ```sh + make px4_sitl sihsim_hex + ``` + + - Fixed-wing (plane) ```sh make px4_sitl sihsim_airplane ``` - - XVert VTOL tailsitter: + - XVert VTOL tailsitter ```sh make px4_sitl sihsim_xvert ``` - - Standard VTOL: + - 标准垂起固定翼 ```sh make px4_sitl sihsim_standard_vtol @@ -235,7 +242,8 @@ For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init. The dynamic models for the various vehicles are: -- Quadrotor: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). +- Quadcopter: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). +- Hexacopter: Equivalent to the Quadcopter but with a symmetric hexacopter x actuation setup. - Fixed-wing: Inspired by the PhD thesis: "Dynamics modeling of agile fixed-wing unmanned aerial vehicles." Khan, Waqas, supervised by Nahon, Meyer, McGill University, PhD thesis, 2016. - Tailsitter: Inspired by the master's thesis: "Modeling and control of a flying wing tailsitter unmanned aerial vehicle." Chiappinelli, Romain, supervised by Nahon, Meyer, McGill University, Masters thesis, 2018. diff --git a/docs/zh/simulation/community_supported_simulators.md b/docs/zh/simulation/community_supported_simulators.md index cf891fa2d6..0fcc37a3c9 100644 --- a/docs/zh/simulation/community_supported_simulators.md +++ b/docs/zh/simulation/community_supported_simulators.md @@ -12,10 +12,10 @@ See [Toolchain Installation](../dev_setup/dev_env.md) for information about the 这些工具有来自其社区的不同程度的支持 (有些得到很好的支持,有些则没有) 。 Questions about these tools should be raised on the [discussion forums](../contribute/support.md#forums-and-chat) -| 仿真器 | 描述 | -| ---------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| -| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| -| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| -| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a very significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| -| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

An alternative to HITL that offers a hard real-time simulation directly on the hardware autopilot. This simulator is implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih).

Supported Vehicles: Plane, Quad, Tailsitter, Standard VTOL

| +| 仿真器 | 描述 | +| ---------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL

| +| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| +| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| +| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| +| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a very significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| From 1277cf28bbf1d75cdde2d7ab3b8c8680b02888b9 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Thu, 22 May 2025 07:50:01 +1000 Subject: [PATCH 024/130] New Crowdin translations - uk (#24894) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 1 + docs/uk/debug/failure_injection.md | 2 +- docs/uk/modules/modules_autotune.md | 8 +- docs/uk/modules/modules_command.md | 177 +++--- docs/uk/modules/modules_communication.md | 28 +- docs/uk/modules/modules_controller.md | 146 ++--- docs/uk/modules/modules_driver.md | 571 ++++++------------ .../modules/modules_driver_airspeed_sensor.md | 28 +- docs/uk/modules/modules_driver_baro.md | 60 +- docs/uk/modules/modules_driver_camera.md | 4 +- .../modules/modules_driver_distance_sensor.md | 136 ++--- docs/uk/modules/modules_driver_imu.md | 136 ++--- docs/uk/modules/modules_driver_ins.md | 6 +- .../uk/modules/modules_driver_magnetometer.md | 56 +- .../uk/modules/modules_driver_optical_flow.md | 6 +- .../modules/modules_driver_radio_control.md | 122 ++++ docs/uk/modules/modules_driver_rpm_sensor.md | 4 +- docs/uk/modules/modules_driver_transponder.md | 4 +- docs/uk/modules/modules_estimator.md | 20 +- docs/uk/modules/modules_simulation.md | 4 +- docs/uk/modules/modules_system.md | 308 ++++------ docs/uk/modules/modules_template.md | 10 +- docs/uk/sim_sih/index.md | 22 +- .../community_supported_simulators.md | 14 +- 24 files changed, 722 insertions(+), 1151 deletions(-) create mode 100644 docs/uk/modules/modules_driver_radio_control.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index 8217225a0b..59a0844b23 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -739,6 +739,7 @@ - [Магнітометр](modules/modules_driver_magnetometer.md) - [Оптичний потік](modules/modules_driver_optical_flow.md) - [Датчик швидкості обертання](modules/modules_driver_rpm_sensor.md) + - [Radio Control](modules/modules_driver_radio_control.md) - [Транспондер](modules/modules_driver_transponder.md) - [Естіматори](modules/modules_estimator.md) - [Симуляції](modules/modules_simulation.md) diff --git a/docs/uk/debug/failure_injection.md b/docs/uk/debug/failure_injection.md index 65cd6e3506..2cfc45ccad 100644 --- a/docs/uk/debug/failure_injection.md +++ b/docs/uk/debug/failure_injection.md @@ -61,7 +61,7 @@ failure [-i ] - _instance number_ (optional): Instance number of affected sensor. 0 (за замовчуванням) вказує на всі сенсори вказаного типу. -### Приклад +### Example Щоб симулювати втрату сигналу RC без вимкнення вашого пульта керування RC: diff --git a/docs/uk/modules/modules_autotune.md b/docs/uk/modules/modules_autotune.md index 17b4b5fac2..b11ba1bc53 100644 --- a/docs/uk/modules/modules_autotune.md +++ b/docs/uk/modules/modules_autotune.md @@ -6,9 +6,7 @@ Source: [modules/fw_autotune_attitude_control](https://github.com/PX4/PX4-Autopi ### Опис - - -### Використання +### Usage {#fw_autotune_attitude_control_usage} ``` fw_autotune_attitude_control [arguments...] @@ -27,9 +25,7 @@ Source: [modules/mc_autotune_attitude_control](https://github.com/PX4/PX4-Autopi ### Опис - - -### Використання +### Usage {#mc_autotune_attitude_control_usage} ``` mc_autotune_attitude_control [arguments...] diff --git a/docs/uk/modules/modules_command.md b/docs/uk/modules/modules_command.md index 97b9c45610..f7e8f84f0b 100644 --- a/docs/uk/modules/modules_command.md +++ b/docs/uk/modules/modules_command.md @@ -8,9 +8,7 @@ Source: [systemcmds/actuator_test](https://github.com/PX4/PX4-Autopilot/tree/mai ПОПЕРЕДЖЕННЯ: перед використанням цієї команди приберіть усі пропелери. - - -### Використання +### Usage {#actuator_test_usage} ``` actuator_test [arguments...] @@ -34,9 +32,9 @@ actuator_test [arguments...] Source: [systemcmds/bl_update](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bl_update) -Utility to flash the bootloader from a file +Utility to flash the bootloader from a file -### Використання +### Usage {#bl_update_usage} ``` bl_update [arguments...] @@ -50,9 +48,9 @@ bl_update [arguments...] Source: [systemcmds/bsondump](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bsondump) -Utility to read BSON from a file and print or output document size. +Utility to read BSON from a file and print or output document size. -### Використання +### Usage {#bsondump_usage} ``` bsondump [arguments...] @@ -63,9 +61,9 @@ bsondump [arguments...] Source: [systemcmds/dumpfile](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dumpfile) -Утиліта для роботи з файлами дампу. Виводить розмір та вміст файлу у бінарному режимі (не замінюйте LF на CR LF) до stdout. +Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. -### Використання +### Usage {#dumpfile_usage} ``` dumpfile [arguments...] @@ -78,17 +76,15 @@ Source: [systemcmds/dyn](https://github.com/PX4/PX4-Autopilot/tree/main/src/syst ### Опис -Завантажує та запускає динамічний модуль PX4, який не було скомпільовано у бінарний файл PX4. +Load and run a dynamic PX4 module, which was not compiled into the PX4 binary. -### Приклад +### Example ``` dyn ./hello.px4mod start ``` - - -### Використання +### Usage {#dyn_usage} ``` dyn [arguments...] @@ -102,21 +98,19 @@ Source: [systemcmds/failure](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### Опис -Впроваджує збої в систему. +Inject failures into system. ### Імплементація -Ця системна команда надсилає транспортному засобу команду через uORB, щоб спровокувати збій. +This system command sends a vehicle command over uORB to trigger failure. ### Приклади -Перевірити failsafe GPS, зупинивши GPS: +Test the GPS failsafe by stopping GPS: failure gps off - - -### Використання +### Usage {#failure_usage} ``` failure [arguments...] @@ -135,7 +129,7 @@ Source: [systemcmds/gpio](https://github.com/PX4/PX4-Autopilot/tree/main/src/sys ### Опис -Ця команда використовується для читання та запису GPIO +This command is used to read and write GPIOs ``` gpio read / [PULLDOWN|PULLUP] [--force] @@ -144,7 +138,7 @@ gpio write / [PUSHPULL|OPENDRAIN] [--force] ### Приклади -Зчитати значення на port H pin 4 налаштований як імпульс, і це високо +Read the value on port H pin 4 configured as pullup, and it is high ``` gpio read H4 PULLUP @@ -152,21 +146,19 @@ gpio read H4 PULLUP 1 OK -Встановіть вихідне значення на виводі порту E на високий рівень +Set the output value on Port E pin 7 to high ``` gpio write E7 1 --force ``` -Встановіть вихідне значення на пристрої /dev/gpio1 на високе значення +Set the output value on device /dev/gpio1 to high ``` gpio write /dev/gpio1 1 ``` - - -### Використання +### Usage {#gpio_usage} ``` gpio [arguments...] @@ -186,13 +178,11 @@ gpio [arguments...] Source: [systemcmds/hardfault_log](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hardfault_log) -Утиліта апаратного збою +Hardfault utility -Використовується у сценаріях запуску для обробки апаратних збоїв +Used in startup scripts to handle hardfaults - - -### Використання +### Usage {#hardfault_log_usage} ``` hardfault_log [arguments...] @@ -219,9 +209,9 @@ hardfault_log [arguments...] Source: [systemcmds/hist](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hist) -Інструмент командного рядка для відображення історії повідомлень px4. Немає аргументів. +Command-line tool to show the px4 message history. There are no arguments. -### Використання +### Usage {#hist_usage} ``` hist [arguments...] @@ -231,9 +221,9 @@ hist [arguments...] Source: [systemcmds/i2cdetect](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/i2cdetect) -Utility to scan for I2C devices on a particular bus. +Utility to scan for I2C devices on a particular bus. -### Використання +### Usage {#i2cdetect_usage} ``` i2cdetect [arguments...] @@ -249,23 +239,21 @@ Source: [systemcmds/led_control](https://github.com/PX4/PX4-Autopilot/tree/main/ Command-line tool to control & test the (external) LED's. -Щоб скористатися ним, переконайтеся, що запущено драйвер, який обробляє тему led_control uorb. +To use it make sure there's a driver running, which handles the led_control uorb topic. -Існують різні пріоритети, наприклад, один модуль може встановити колір з низьким пріоритетом, а інший -модуль може блимати N разів з високим пріоритетом, і світлодіоди автоматично повертаються до стану з низьким пріоритетом -після блимання. The `reset` command can also be used to return to a lower priority. +There are different priorities, such that for example one module can set a color with low priority, and another +module can blink N times with high priority, and the LED's automatically return to the lower priority state +after the blinking. The `reset` command can also be used to return to a lower priority. ### Приклади -Блимання першого світлодіода 5 разів синім кольором: +Blink the first LED 5 times in blue: ``` led_control blink -c blue -l 0 -n 5 ``` - - -### Використання +### Usage {#led_control_usage} ``` led_control [arguments...] @@ -301,13 +289,11 @@ led_control [arguments...] Source: [systemcmds/topic_listener](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/topic_listener) -Утиліта для прослуховування тем uORB та виводу даних у консоль. +Utility to listen on uORB topics and print the data to the console. -Із прослуховування можна вийти в будь-який момент, натиснувши Ctrl+C, Esc або Q. +The listener can be exited any time by pressing Ctrl+C, Esc, or Q. - - -### Використання +### Usage {#listener_usage} ``` listener [arguments...] @@ -325,9 +311,9 @@ listener [arguments...] Source: [systemcmds/mft](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft) -Utility interact with the manifest +Utility interact with the manifest -### Використання +### Usage {#mfd_usage} ``` mfd [arguments...] @@ -339,9 +325,9 @@ mfd [arguments...] Source: [systemcmds/mft_cfg](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft_cfg) -Tool to set and get manifest configuration +Tool to set and get manifest configuration -### Використання +### Usage {#mft_cfg_usage} ``` mft_cfg [arguments...] @@ -360,9 +346,9 @@ mft_cfg [arguments...] Source: [systemcmds/mtd](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mtd) -Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) +Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) -### Використання +### Usage {#mtd_usage} ``` mtd [arguments...] @@ -388,14 +374,12 @@ mtd [arguments...] Source: [systemcmds/nshterm](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/nshterm) -Запуск оболонки NSH на заданому порту. +Start an NSH shell on a given port. -Раніше це використовувалося для запуску оболонки на послідовному порту USB. -Тепер там працює mavlink, і можна використовувати оболонку поверх mavlink. +This was previously used to start a shell on the USB serial port. +Now there runs mavlink, and it is possible to use a shell over mavlink. - - -### Використання +### Usage {#nshterm_usage} ``` nshterm [arguments...] @@ -408,23 +392,24 @@ Source: [systemcmds/param](https://github.com/PX4/PX4-Autopilot/tree/main/src/sy ### Опис -Команда для доступу до параметрів і маніпулювання ними через оболонку або скрипт. +Command to access and manipulate parameters via shell or script. -Це використовується, наприклад, у сценарії запуску для встановлення специфічних для планера параметрів. +This is used for example in the startup script to set airframe-specific parameters. -Parameters are automatically saved when changed, eg. with `param set`. Зазвичай вони зберігаються на FRAM -або на SD-карту. `param select` can be used to change the storage location for subsequent saves (this will +Parameters are automatically saved when changed, eg. with `param set`. They are typically stored to FRAM +or to the SD card. `param select` can be used to change the storage location for subsequent saves (this will need to be (re-)configured on every boot). If the FLASH-based backend is enabled (which is done at compile time, e.g. for the Intel Aero or Omnibus), `param select` has no effect and the default is always the FLASH backend. However `param save/load ` can still be used to write to/read from files. -Кожен параметр має прапорець «використано», який встановлюється при його зчитуванні під час завантаження. Він використовується для відображення лише релевантних параметрів на наземну станцію керування. +Each parameter has a 'used' flag, which is set when it's read during boot. It is used to only show relevant +parameters to a ground control station. ### Приклади -Змініть планер і переконайтеся, що завантажені параметри планера за замовчуванням: +Change the airframe and make sure the airframe's default parameters are loaded: ``` param set SYS_AUTOSTART 4001 @@ -432,9 +417,7 @@ param set SYS_AUTOCONFIG 1 reboot ``` - - -### Використання +### Usage {#param_usage} ``` param [arguments...] @@ -509,12 +492,10 @@ Source: [modules/payload_deliverer](https://github.com/PX4/PX4-Autopilot/tree/ma ### Опис -Керує доставкою вантажу за допомогою захвату або лебідки з відповідним налаштуванням тайм-ауту / датчиком зворотнього зв'язку, -та повертає результат доставки як підтвердження внутрішньо +Handles payload delivery with either Gripper or a Winch with an appropriate timeout / feedback sensor setting, +and communicates back the delivery result as an acknowledgement internally - - -### Використання +### Usage {#payload_deliverer_usage} ``` payload_deliverer [arguments...] @@ -536,9 +517,9 @@ payload_deliverer [arguments...] Source: [systemcmds/perf](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/perf) -Tool to print performance counters +Tool to print performance counters -### Використання +### Usage {#perf_usage} ``` perf [arguments...] @@ -553,9 +534,9 @@ perf [arguments...] Source: [systemcmds/reboot](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/reboot) -Reboot the system +Reboot the system -### Використання +### Usage {#reboot_usage} ``` reboot [arguments...] @@ -568,9 +549,9 @@ reboot [arguments...] Source: [systemcmds/sd_bench](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_bench) -Test the speed of an SD Card +Test the speed of an SD Card -### Використання +### Usage {#sd_bench_usage} ``` sd_bench [arguments...] @@ -591,9 +572,9 @@ sd_bench [arguments...] Source: [systemcmds/sd_stress](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_stress) -Test operations on an SD Card +Test operations on an SD Card -### Використання +### Usage {#sd_stress_usage} ``` sd_stress [arguments...] @@ -607,13 +588,11 @@ sd_stress [arguments...] Source: [systemcmds/serial_passthru](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/serial_passthru) -Передає дані з одного пристрою на інший. +Pass data from one device to another. -Це може бути використано для використання u-center, підключеного до USB з GPS через послідовний порт. +This can be used to use u-center connected to USB with a GPS on a serial port. - - -### Використання +### Usage {#serial_passthru_usage} ``` serial_passthru [arguments...] @@ -632,20 +611,18 @@ Source: [systemcmds/system_time](https://github.com/PX4/PX4-Autopilot/tree/main/ ### Опис -Інструмент командного рядка для встановлення та отримання системного часу. +Command-line tool to set and get system time. ### Приклади -Встановіть системний час і прочитайте його назад +Set the system time and read it back ``` system_time set 1600775044 system_time get ``` - - -### Використання +### Usage {#system_time_usage} ``` system_time [arguments...] @@ -659,9 +636,9 @@ system_time [arguments...] Source: [systemcmds/top](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/top) -Monitor running processes and their CPU, stack usage, priority and state +Monitor running processes and their CPU, stack usage, priority and state -### Використання +### Usage {#top_usage} ``` top [arguments...] @@ -672,10 +649,10 @@ top [arguments...] Source: [systemcmds/usb_connected](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/usb_connected) -Утиліта для перевірки підключення USB. Раніше використовувався в стартових скриптах. -Значення 0 означає, що USB підключено, 1 - ні. +Utility to check if USB is connected. Was previously used in startup scripts. +A return value of 0 means USB is connected, 1 otherwise. -### Використання +### Usage {#usb_connected_usage} ``` usb_connected [arguments...] @@ -685,9 +662,9 @@ usb_connected [arguments...] Source: [systemcmds/ver](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/ver) -Tool to print various version information +Tool to print various version information -### Використання +### Usage {#ver_usage} ``` ver [arguments...] diff --git a/docs/uk/modules/modules_communication.md b/docs/uk/modules/modules_communication.md index 50021d207d..e1d4fcebe4 100644 --- a/docs/uk/modules/modules_communication.md +++ b/docs/uk/modules/modules_communication.md @@ -4,9 +4,9 @@ Source: [drivers/telemetry/frsky_telemetry](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/frsky_telemetry) -Підтримка FrSky Telemetry. Автоматичне визначення протоколу D або S.PORT. +Підтримка FrSky Telemetry. Автоматичне визначення протоколу D або S.PORT. -### Використання +### Usage {#frsky_telemetry_usage} ``` frsky_telemetry [arguments...] @@ -64,9 +64,7 @@ mavlink start -u 14556 -r 1000000 mavlink stream -u 14556 -s HIGHRES_IMU -r 50 ``` - - -### Використання +### Usage {#mavlink_usage} ``` mavlink [arguments...] @@ -129,31 +127,29 @@ Source: [systemcmds/uorb](https://github.com/PX4/PX4-Autopilot/tree/main/src/sys ### Опис -uORB - це внутрішня система обміну повідомленнями pub-sub, яка використовується для комунікації між модулями. +uORB is the internal pub-sub messaging system, used for communication between modules. ### Імплементація -Реалізація є асинхронною та безблоковою, тобто видавець не чекає на підписника і навпаки. -Це досягається завдяки наявності окремого буфера між публікатором і підписником. +The implementation is asynchronous and lock-free, ie. a publisher does not wait for a subscriber and vice versa. +This is achieved by having a separate buffer between a publisher and a subscriber. -Код оптимізовано для мінімізації використання пам'яті та затримок при обміні повідомленнями. +The code is optimized to minimize the memory footprint and the latency to exchange messages. -Messages are defined in the `/msg` directory. Вони перетворюються в код C/C++ під час збірки. +Messages are defined in the `/msg` directory. They are converted into C/C++ code at build-time. -Якщо ви компілюєте з ORB_USE_PUBLISHER_RULES, файл з правилами публікації uORB можна використовувати для налаштування того, яким -модулям дозволено публікувати які теми. Це використовується для загальносистемного відтворення. +If compiled with ORB_USE_PUBLISHER_RULES, a file with uORB publication rules can be used to configure which +modules are allowed to publish which topics. This is used for system-wide replay. ### Приклади -Відстежуйте показники публікацій тем. Besides `top`, this is an important command for general system inspection: +Monitor topic publication rates. Besides `top`, this is an important command for general system inspection: ``` uorb top ``` - - -### Використання +### Usage {#uorb_usage} ``` uorb [arguments...] diff --git a/docs/uk/modules/modules_controller.md b/docs/uk/modules/modules_controller.md index cbfdbd4177..6ae0e1a0b1 100644 --- a/docs/uk/modules/modules_controller.md +++ b/docs/uk/modules/modules_controller.md @@ -16,9 +16,7 @@ Currently it is feeding the `manual_control_setpoint` topic directly to the actu Щоб зменшити затримку керування, модуль безпосередньо опитує тему гіроскопа, опубліковану драйвером IMU. - - -### Використання +### Usage {#airship_att_control_usage} ``` airship_att_control [arguments...] @@ -36,12 +34,10 @@ Source: [modules/control_allocator](https://github.com/PX4/PX4-Autopilot/tree/ma ### Опис -Це реалізує розподіл управління. Він приймає задані значення крутного моменту та тяги -як вхідні та вихідні повідомлення про задані значення привода. +This implements control allocation. It takes torque and thrust setpoints +as inputs and outputs actuator setpoint messages. - - -### Використання +### Usage {#control_allocator_usage} ``` control_allocator [arguments...] @@ -59,12 +55,10 @@ Source: [modules/flight_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/ ### Опис -Це реалізує генерацію заданого значення для всіх режимів. Він приймає поточний стан режиму транспортного засобу як вхідні дані -і виводить задані значення для контролерів. +This implements the setpoint generation for all modes. It takes the current mode state of the vehicle as input +and outputs setpoints for controllers. - - -### Використання +### Usage {#flight_mode_manager_usage} ``` flight_mode_manager [arguments...] @@ -82,11 +76,9 @@ Source: [modules/fw_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### Опис -fw_att_control - регулятор положення фіксованого крила. +fw_att_control is the fixed wing attitude controller. - - -### Використання +### Usage {#fw_att_control_usage} ``` fw_att_control [arguments...] @@ -105,11 +97,9 @@ Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### Опис -fw_pos_control - контролер положення фіксованого крила. +fw_pos_control is the fixed-wing position controller. - - -### Використання +### Usage {#fw_pos_control_usage} ``` fw_pos_control [arguments...] @@ -128,11 +118,9 @@ Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main ### Опис -fw_rate_control - регулятор швидкості фіксованого крила. +fw_rate_control is the fixed-wing rate controller. - - -### Використання +### Usage {#fw_rate_control_usage} ``` fw_rate_control [arguments...] @@ -151,21 +139,19 @@ Source: [modules/mc_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### Опис -Це реалізує контролер положення мультикоптера. It takes attitude +This implements the multicopter attitude controller. It takes attitude setpoints (`vehicle_attitude_setpoint`) as inputs and outputs a rate setpoint. -Контролер має P цикл для кутової похибки +The controller has a P loop for angular error -Публікація, що документує реалізоване кватерніонне керування положенням: +Publication documenting the implemented Quaternion Attitude Control: Nonlinear Quadrocopter Attitude Control (2013) by Dario Brescianini, Markus Hehn and Raffaello D'Andrea Institute for Dynamic Systems and Control (IDSC), ETH Zurich https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf - - -### Використання +### Usage {#mc_att_control_usage} ``` mc_att_control [arguments...] @@ -184,16 +170,14 @@ Source: [modules/mc_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### Опис -Контролер має два контури: P цикл для помилки положення і PID цикл для помилки швидкості. -Виходом контролера швидкості є вектор тяги, який розділяється на напрямок тяги -(тобто матрицю обертання для орієнтації мультикоптера) та скаляр тяги (тобто саму тягу мультикоптера). +The controller has two loops: a P loop for position error and a PID loop for velocity error. +Output of the velocity controller is thrust vector that is split to thrust direction +(i.e. rotation matrix for multicopter orientation) and thrust scalar (i.e. multicopter thrust itself). -Контролер не використовує кути Ейлера для своєї роботи, вони генеруються лише для більш зручного керування та -логування. +The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and +logging. - - -### Використання +### Usage {#mc_pos_control_usage} ``` mc_pos_control [arguments...] @@ -212,14 +196,12 @@ Source: [modules/mc_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main ### Опис -Це реалізує мультикоптерний регулятор швидкості. It takes rate setpoints (in acro mode +This implements the multicopter rate controller. It takes rate setpoints (in acro mode via `manual_control_setpoint` topic) as inputs and outputs actuator control messages. -Контролер має PID-цикл для компенсації похибки кутової швидкості. +The controller has a PID loop for angular rate error. - - -### Використання +### Usage {#mc_rate_control_usage} ``` mc_rate_control [arguments...] @@ -238,9 +220,9 @@ Source: [modules/navigator](https://github.com/PX4/PX4-Autopilot/tree/main/src/m ### Опис -Модуль відповідає за автономні режими польоту. Це включає місії (читайте з dataman), -взліт та RTL. -Він також відповідає за перевірку порушень геозони. +Module that is responsible for autonomous flight modes. This includes missions (read from dataman), +takeoff and RTL. +It is also responsible for geofence violation checking. ### Імплементація @@ -250,9 +232,7 @@ The member `_navigation_mode` contains the current active mode. Navigator publishes position setpoint triplets (`position_setpoint_triplet_s`), which are then used by the position controller. - - -### Використання +### Usage {#navigator_usage} ``` navigator [arguments...] @@ -276,9 +256,7 @@ Source: [modules/rover_ackermann](https://github.com/PX4/PX4-Autopilot/tree/main Rover ackermann module. - - -### Використання +### Usage {#rover_ackermann_usage} ``` rover_ackermann [arguments...] @@ -298,9 +276,7 @@ Source: [modules/rover_differential](https://github.com/PX4/PX4-Autopilot/tree/m Rover differential module. - - -### Використання +### Usage {#rover_differential_usage} ``` rover_differential [arguments...] @@ -320,9 +296,7 @@ Source: [modules/rover_mecanum](https://github.com/PX4/PX4-Autopilot/tree/main/s Rover mecanum module. - - -### Використання +### Usage {#rover_mecanum_usage} ``` rover_mecanum [arguments...] @@ -340,21 +314,21 @@ Source: [modules/rover_pos_control](https://github.com/PX4/PX4-Autopilot/tree/ma ### Опис -Контролює положення ровера за допомогою L1 контролера. +Controls the position of a ground rover using an L1 controller. Publishes `vehicle_thrust_setpoint (only in x) and vehicle_torque_setpoint (only yaw)` messages at IMU_GYRO_RATEMAX. ### Імплементація -Наразі ця реалізація підтримує лише декілька режимів: +Currently, this implementation supports only a few modes: -- Повна ручна: Throttle та yaw контроль передається безпосередньо на актуатори -- Автоматична місія: Ровер виконує місії -- Loiter: Ровер буде рухатися в межах радіусу очікування, а потім вимкне двигуни +- Full manual: Throttle and yaw controls are passed directly through to the actuators +- Auto mission: The rover runs missions +- Loiter: The rover will navigate to within the loiter radius, then stop the motors ### Приклади -Приклад використання CLI: +CLI usage example: ``` rover_pos_control start @@ -362,9 +336,7 @@ rover_pos_control status rover_pos_control stop ``` - - -### Використання +### Usage {#rover_pos_control_usage} ``` rover_pos_control [arguments...] @@ -387,9 +359,7 @@ It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages. ``` - - -### Використання +### Usage {#spacecraft_usage} ``` spacecraft [arguments...] @@ -407,20 +377,20 @@ Source: [modules/uuv_att_control](https://github.com/PX4/PX4-Autopilot/tree/main ### Опис -Контролює положення безпілотного підводного апарату (UUV). +Controls the attitude of an unmanned underwater vehicle (UUV). Publishes `vehicle_thrust_setpont` and `vehicle_torque_setpoint` messages at a constant 250Hz. ### Імплементація -Наразі ця реалізація підтримує лише декілька режимів: +Currently, this implementation supports only a few modes: -- Повна ручна: Roll, pitch, yaw, та throttle контроль передається безпосередньо до актуаторів -- Автоматична місія: UUV виконує місії +- Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators +- Auto mission: The uuv runs missions ### Приклади -Приклад використання CLI: +CLI usage example: ``` uuv_att_control start @@ -428,9 +398,7 @@ uuv_att_control status uuv_att_control stop ``` - - -### Використання +### Usage {#uuv_att_control_usage} ``` uuv_att_control [arguments...] @@ -448,19 +416,19 @@ Source: [modules/uuv_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main ### Опис -Контролює положення безпілотного підводного апарату (UUV). +Controls the attitude of an unmanned underwater vehicle (UUV). Publishes `attitude_setpoint` messages. ### Імплементація -Наразі ця реалізація підтримує лише декілька режимів: +Currently, this implementation supports only a few modes: -- Повна ручна: Roll, pitch, yaw, та throttle контроль передається безпосередньо до актуаторів -- Автоматична місія: UUV виконує місії +- Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators +- Auto mission: The uuv runs missions ### Приклади -Приклад використання CLI: +CLI usage example: ``` uuv_pos_control start @@ -468,9 +436,7 @@ uuv_pos_control status uuv_pos_control stop ``` - - -### Використання +### Usage {#uuv_pos_control_usage} ``` uuv_pos_control [arguments...] @@ -488,11 +454,9 @@ Source: [modules/vtol_att_control](https://github.com/PX4/PX4-Autopilot/tree/mai ### Опис -fw_att_control - регулятор положення фіксованого крила. +fw_att_control is the fixed wing attitude controller. - - -### Використання +### Usage {#vtol_att_control_usage} ``` vtol_att_control [arguments...] diff --git a/docs/uk/modules/modules_driver.md b/docs/uk/modules/modules_driver.md index 9542c16fc4..59002c651e 100644 --- a/docs/uk/modules/modules_driver.md +++ b/docs/uk/modules/modules_driver.md @@ -3,23 +3,22 @@ Підкатегорії: - [Airspeed Sensor](modules_driver_airspeed_sensor.md) -- [Transponder](modules_driver_transponder.md) -- [Imu](modules_driver_imu.md) -- [Rpm Sensor](modules_driver_rpm_sensor.md) -- [Magnetometer](modules_driver_magnetometer.md) +- [Baro](modules_driver_baro.md) - [Camera](modules_driver_camera.md) - [Distance Sensor](modules_driver_distance_sensor.md) -- [Optical Flow](modules_driver_optical_flow.md) +- [Imu](modules_driver_imu.md) - [Ins](modules_driver_ins.md) -- [Baro](modules_driver_baro.md) +- [Magnetometer](modules_driver_magnetometer.md) +- [Optical Flow](modules_driver_optical_flow.md) +- [Radio Control](modules_driver_radio_control.md) +- [Rpm Sensor](modules_driver_rpm_sensor.md) +- [Transponder](modules_driver_transponder.md) ## MCP23009 Source: [drivers/gpio/mcp23009](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gpio/mcp23009) - - -### Використання +### Usage {#MCP23009_usage} ``` MCP23009 [arguments...] @@ -53,11 +52,9 @@ Source: [drivers/adc/board_adc](https://github.com/PX4/PX4-Autopilot/tree/main/s ### Опис -ADC драйвер. +ADC driver. - - -### Використання +### Usage {#adc_usage} ``` adc [arguments...] @@ -87,11 +84,9 @@ such as [PilotPi](../flight_controller/raspberry_pi_pilotpi.md) or [CUAV Nora](. It is enabled/disabled using the [ADC_ADS1115_EN](../advanced_config/parameter_reference.md#ADC_ADS1115_EN) parameter, and is disabled by default. -Якщо увімкнено, внутрішні ADC не використовуються. +If enabled, internal ADCs are not used. - - -### Використання +### Usage {#ads1115_usage} ``` ads1115 [arguments...] @@ -117,13 +112,11 @@ Source: [drivers/osd/atxxxx](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### Опис -Наприклад, OSD драйвер для мікросхеми ATXXXX, яка встановлена на платі OmnibusF4SD. +OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example. -Його можна увімкнути за допомогою параметра OSD_ATXXXX_CFG. +It can be enabled with the OSD_ATXXXX_CFG parameter. - - -### Використання +### Usage {#atxxxx_usage} ``` atxxxx [arguments...] @@ -149,20 +142,18 @@ Source: [drivers/smart_battery/batmon](https://github.com/PX4/PX4-Autopilot/tree ### Опис -Драйвер для зв'язку SMBUS зі смарт-батареєю з підтримкою BatMon -Інформація про налаштування/використання: https://rotoye.com/batmon-tutorial/ +Driver for SMBUS Communication with BatMon enabled smart-battery +Setup/usage information: https://rotoye.com/batmon-tutorial/ ### Приклади -Почати з адреси 0x0B, на шині 4 +To start at address 0x0B, on bus 4 ``` batmon start -X -a 11 -b 4 ``` - - -### Використання +### Usage {#batmon_usage} ``` batmon [arguments...] @@ -194,19 +185,17 @@ Source: [drivers/batt_smbus](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### Опис -Розумний драйвер акумулятора для BQ40Z50 палива IC. +Smart battery driver for the BQ40Z50 fuel gauge IC. ### Приклади -Записати у прошивку для встановлення параметрів. address, number_of_bytes, byte0, ... , byteN +To write to flash to set parameters. address, number_of_bytes, byte0, ... , byteN ``` batt_smbus -X write_flash 19069 2 27 0 ``` - - -### Використання +### Usage {#batt_smbus_usage} ``` batt_smbus [arguments...] @@ -247,9 +236,7 @@ batt_smbus [arguments...] Source: [drivers/telemetry/bst](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/bst) - - -### Використання +### Usage {#bst_usage} ``` bst [arguments...] @@ -269,62 +256,36 @@ bst [arguments...] status print status info ``` -## crsf_rc - -Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) - -### Опис - -Цей модуль парсить uplink протокол CRSF RC і генерує дані CRSF downlink телеметрії - - - -### Використання - -``` -crsf_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## dshot Source: [drivers/dshot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/dshot) ### Опис -Це драйвер виводу DShot. Він схожий на драйвер fmu і може бути використаний як заміна -використовувати DShot як протокол зв'язку ESC замість PWM. +This is the DShot output driver. It is similar to the fmu driver, and can be used as drop-in replacement +to use DShot as ESC communication protocol instead of PWM. -Під час запуску модуль намагається зайняти всі доступні піни для виходу DShot. -Він пропускає всі піни, які вже використовуються (наприклад, модулем запуску камери). +On startup, the module tries to occupy all available pins for DShot output. +It skips all pins already in use (e.g. by a camera trigger module). -Він підтримує: +It supports: - DShot150, DShot300, DShot600 -- телеметрія через окремий UART та публікація у вигляді повідомлення esc_status -- надсилання команд DShot через CLI +- telemetry via separate UART and publishing as esc_status message +- sending DShot commands via CLI ### Приклади -Постійно реверсує двигун 1: +Permanently reverse motor 1: ``` dshot reverse -m 1 dshot save -m 1 ``` -Після збереження змінений напрямок буде вважатися нормальним. Щоб розвернути назад, повторіть ті ж самі команди. +After saving, the reversed direction will be regarded as the normal one. So to reverse again repeat the same commands. - - -### Використання +### Usage {#dshot_usage} ``` dshot [arguments...] @@ -372,41 +333,13 @@ dshot [arguments...] status print status info ``` -## dsm_rc - -Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) - -### Опис - -This module does Spektrum DSM RC input parsing. - - - -### Використання - -``` -dsm_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` - ## fake_gps Source: [examples/fake_gps](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/fake_gps) ### Опис - - -### Використання +### Usage {#fake_gps_usage} ``` fake_gps [arguments...] @@ -424,9 +357,7 @@ Source: [examples/fake_imu](https://github.com/PX4/PX4-Autopilot/tree/main/src/e ### Опис - - -### Використання +### Usage {#fake_imu_usage} ``` fake_imu [arguments...] @@ -445,11 +376,9 @@ Source: [examples/fake_magnetometer](https://github.com/PX4/PX4-Autopilot/tree/m ### Опис Publish the earth magnetic field as a fake magnetometer (sensor_mag). -Потребує vehicle_attitude та vehicle_gps_position. +Requires vehicle_attitude and vehicle_gps_position. - - -### Використання +### Usage {#fake_magnetometer_usage} ``` fake_magnetometer [arguments...] @@ -467,14 +396,14 @@ Source: [drivers/wind_sensor/ft_technologies](https://github.com/PX4/PX4-Autopil ### Опис -Драйвер послідовної шини для цифрового датчика вітру FT Technologies FT742. Цей драйвер потрібен для роботи разом з -з модулем передачі сигналу RS485 на UART. +Serial bus driver for the FT Technologies Digital Wind Sensor FT742. This driver is required to operate alongside +a RS485 to UART signal transfer module. -Більшість плат налаштовано на увімкнення/запуск драйвера на вказаному UART за допомогою параметра SENS_FTX_CFG. +Most boards are configured to enable/start the driver on a specified UART using the SENS_FTX_CFG parameter. ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` ft_technologies_serial start -d /dev/ttyS1 @@ -486,9 +415,7 @@ Stop driver ft_technologies_serial stop ``` - - -### Використання +### Usage {#ft_technologies_serial_usage} ``` ft_technologies_serial [arguments...] @@ -499,51 +426,26 @@ ft_technologies_serial [arguments...] stop Stop driver ``` -## ghst_rc - -Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) - -### Опис - -This module does Ghost (GHST) RC input parsing. - - - -### Використання - -``` -ghst_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## gimbal Source: [modules/gimbal](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/gimbal) ### Опис -Водій керування монтажем / гімбалю. Він відображає кілька різних методів введення (наприклад, RC або MAVLink) на налаштований вивід (наприклад, AUX канали або MAVLink). +Mount/gimbal Gimbal control driver. It maps several different input methods (eg. RC or MAVLink) to a configured +output (eg. AUX channels or MAVLink). Documentation how to use it is on the [gimbal_control](https://docs.px4.io/main/en/advanced/gimbal_control.html) page. ### Приклади -Перевірте вихідні дані, встановивши кути (всі пропущені вісі установлені на 0): +Test the output by setting a angles (all omitted axes are set to 0): ``` gimbal test pitch -45 yaw 30 ``` - - -### Використання +### Usage {#gimbal_usage} ``` gimbal [arguments...] @@ -572,35 +474,33 @@ Source: [drivers/gps](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers ### Опис -Модуль GPS-драйвера, який здійснює зв'язок з пристроєм і публікує позицію через uORB. -Він підтримує кілька протоколів (постачальників пристроїв) і за замовчуванням автоматично вибирає правильний. +GPS driver module that handles the communication with the device and publishes the position via uORB. +It supports multiple protocols (device vendors) and by default automatically selects the correct one. -The module supports a secondary GPS device, specified via `-e` parameter. Позиція буде опублікована -на другому екземплярі теми uORB, але наразі вона не використовується рештою системи (однак -дані будуть зареєстровані, щоб їх можна було використовувати для порівняння). +The module supports a secondary GPS device, specified via `-e` parameter. The position will be published +on the second uORB topic instance, but it's currently not used by the rest of the system (however the +data will be logged, so that it can be used for comparisons). ### Імплементація -Для кожного пристрою існує потік, який опитує дані. Класи протоколу GPS реалізовано з функцією зворотного виклику -щоб їх можна було використовувати і в інших проектах (наприклад, QGroundControl також використовує їх). +There is a thread for each device polling for data. The GPS protocol classes are implemented with callbacks +so that they can be used in other projects as well (eg. QGroundControl uses them too). ### Приклади -Запуск 2 GPS-пристроїв (основний GPS на /dev/ttyS3 і додатковий на /dev/ttyS4): +Starting 2 GPS devices (the main GPS on /dev/ttyS3 and the secondary on /dev/ttyS4): ``` gps start -d /dev/ttyS3 -e /dev/ttyS4 ``` -Ініціюйте гарячий перезапуск GPS-пристрою +Initiate warm restart of GPS device ``` gps reset warm ``` - - -### Використання +### Usage {#gps_usage} ``` gps [arguments...] @@ -635,9 +535,7 @@ Source: [modules/simulation/gz_bridge](https://github.com/PX4/PX4-Autopilot/tree ### Опис - - -### Використання +### Usage {#gz_bridge_usage} ``` gz_bridge [arguments...] @@ -657,19 +555,18 @@ Source: [drivers/power_monitor/ina220](https://github.com/PX4/PX4-Autopilot/tree ### Опис -Драйвер для монітора живлення INA220. +Driver for the INA220 power monitor. -Кілька екземплярів цього драйвера можуть працювати одночасно, якщо кожен екземпляр має окрему адресу шини АБО I2C. +Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. -Наприклад, один екземпляр може працювати на шині 2, адреса 0x41, а інший - на шині 2, адреса 0x43. +For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43. -Якщо модуль INA220 не має живлення, то за замовчуванням ініціалізація драйвера не відбудеться. Щоб змінити це, використовуйте -прапор -f. Якщо цей прапорець встановлено, то у разі невдалої ініціалізації драйвер буде повторювати спроби ініціалізації -кожні 0.5 секунди. Якщо цей прапорець встановлено, ви можете підключити батарею після запуску драйвера, і він буде працювати. Якщо цей прапорець не встановлено, перед запуском драйвера необхідно підключити батарею. +If the INA220 module is not powered, then by default, initialization of the driver will fail. To change this, use +the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again +every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without +this flag set, the battery must be plugged in before starting the driver. - - -### Використання +### Usage {#ina220_usage} ``` ina220 [arguments...] @@ -700,19 +597,18 @@ Source: [drivers/power_monitor/ina226](https://github.com/PX4/PX4-Autopilot/tree ### Опис -Драйвер для монітора живлення INA226. +Driver for the INA226 power monitor. -Кілька екземплярів цього драйвера можуть працювати одночасно, якщо кожен екземпляр має окрему адресу шини АБО I2C. +Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. -Наприклад, один екземпляр може працювати на шині 2, адреса 0x41, а інший - на шині 2, адреса 0x43. +For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43. -Якщо модуль INA226 не живиться, то за замовчуванням ініціалізація драйвера не відбудеться. Щоб змінити це, використовуйте -прапор -f. Якщо цей прапорець встановлено, то у разі невдалої ініціалізації драйвер буде повторювати спроби ініціалізації -кожні 0.5 секунди. Якщо цей прапорець встановлено, ви можете підключити батарею після запуску драйвера, і він буде працювати. Якщо цей прапорець не встановлено, перед запуском драйвера необхідно підключити батарею. +If the INA226 module is not powered, then by default, initialization of the driver will fail. To change this, use +the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again +every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without +this flag set, the battery must be plugged in before starting the driver. - - -### Використання +### Usage {#ina226_usage} ``` ina226 [arguments...] @@ -741,19 +637,18 @@ Source: [drivers/power_monitor/ina228](https://github.com/PX4/PX4-Autopilot/tree ### Опис -Драйвер для монітора живлення INA228. +Driver for the INA228 power monitor. -Кілька екземплярів цього драйвера можуть працювати одночасно, якщо кожен екземпляр має окрему адресу шини АБО I2C. +Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. -Наприклад, один екземпляр може працювати на шині 2, адреса 0x41, а інший - на шині 2, адреса 0x43. +For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45. -Якщо модуль INA228 не має живлення, то за замовчуванням ініціалізація драйвера не відбудеться. Щоб змінити це, використовуйте -прапор -f. Якщо цей прапорець встановлено, то у разі невдалої ініціалізації драйвер буде повторювати спроби ініціалізації -кожні 0.5 секунди. Якщо цей прапорець встановлено, ви можете підключити батарею після запуску драйвера, і він буде працювати. Якщо цей прапорець не встановлено, перед запуском драйвера необхідно підключити батарею. +If the INA228 module is not powered, then by default, initialization of the driver will fail. To change this, use +the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again +every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without +this flag set, the battery must be plugged in before starting the driver. - - -### Використання +### Usage {#ina228_usage} ``` ina228 [arguments...] @@ -782,19 +677,18 @@ Source: [drivers/power_monitor/ina238](https://github.com/PX4/PX4-Autopilot/tree ### Опис -Драйвер для монітора потужності INA238. +Driver for the INA238 power monitor. -Кілька екземплярів цього драйвера можуть працювати одночасно, якщо кожен екземпляр має окрему адресу шини АБО I2C. +Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. -Наприклад, один екземпляр може працювати на шині 2, адреса 0x41, а інший - на шині 2, адреса 0x43. +For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45. -Якщо модуль INA238 не заснується, то за замовчуванням ініціалізація драйвера не вдасться. Щоб змінити це, використовуйте -прапор -f. Якщо цей прапорець встановлено, то у разі невдалої ініціалізації драйвер буде повторювати спроби ініціалізації -кожні 0.5 секунди. Якщо цей прапорець встановлено, ви можете підключити батарею після запуску драйвера, і він буде працювати. Якщо цей прапорець не встановлено, перед запуском драйвера необхідно підключити батарею. +If the INA238 module is not powered, then by default, initialization of the driver will fail. To change this, use +the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again +every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without +this flag set, the battery must be plugged in before starting the driver. - - -### Використання +### Usage {#ina238_usage} ``` ina238 [arguments...] @@ -823,13 +717,11 @@ Source: [drivers/telemetry/iridiumsbd](https://github.com/PX4/PX4-Autopilot/tree ### Опис -Драйвер IridiumSBD. +IridiumSBD driver. -Створює віртуальний послідовний порт, який інший модуль може використовувати для зв'язку (наприклад, mavlink). +Creates a virtual serial port that another module can use for communication (e.g. mavlink). - - -### Використання +### Usage {#iridiumsbd_usage} ``` iridiumsbd [arguments...] @@ -851,9 +743,7 @@ iridiumsbd [arguments...] Source: [drivers/irlock](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/irlock) - - -### Використання +### Usage {#irlock_usage} ``` irlock [arguments...] @@ -879,11 +769,9 @@ Source: [drivers/linux_pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main/s ### Опис -Драйвер виведення Linux PWM з реалізацією бекенду специфічного для плати. +Linux PWM output driver with board-specific backend implementation. - - -### Використання +### Usage {#linux_pwm_out_usage} ``` linux_pwm_out [arguments...] @@ -899,9 +787,7 @@ linux_pwm_out [arguments...] Source: [drivers/magnetometer/lsm303agr](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm303agr) - - -### Використання +### Usage {#lsm303agr_usage} ``` lsm303agr [arguments...] @@ -929,23 +815,21 @@ Source: [drivers/osd/msp_osd](https://github.com/PX4/PX4-Autopilot/tree/main/src ### Опис -Потік телеметрії MSP +MSP telemetry streamer ### Імплементація -Перетворює повідомлення uORB на пакети телеметрії MSP +Converts uORB messages to MSP telemetry packets ### Приклади -Приклад використання CLI: +CLI usage example: ``` msp_osd ``` - - -### Використання +### Usage {#msp_osd_usage} ``` msp_osd [arguments...] @@ -961,21 +845,19 @@ Source: [drivers/lights/neopixel](https://github.com/PX4/PX4-Autopilot/tree/main ### Опис -Цей модуль відповідає за взаємодію з Neopixel Serial LED +This module is responsible for driving interfasing to the Neopixel Serial LED ### Приклади -Зазвичай починається з: +It is typically started with: ``` neopixel -n 8 ``` -Привести всі доступні світлодіоди в дію. +To drive all available leds. - - -### Використання +### Usage {#newpixel_usage} ``` newpixel [arguments...] @@ -989,9 +871,7 @@ newpixel [arguments...] Source: [drivers/optical_flow/paa3905](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paa3905) - - -### Використання +### Usage {#paa3905_usage} ``` paa3905 [arguments...] @@ -1017,9 +897,7 @@ paa3905 [arguments...] Source: [drivers/optical_flow/paw3902](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paw3902) - - -### Використання +### Usage {#paw3902_usage} ``` paw3902 [arguments...] @@ -1047,25 +925,23 @@ Source: [drivers/pca9685_pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main ### Опис -Це пристрій виводу керування PWM PCA9685. +This is a PCA9685 PWM output driver. -Він працює на робочій черзі I2C, яка є асинхронною з контрольною петлею FC, -витягує останній результат змішування та записує їх в PCA9685 у відповідних мітках планування. +It runs on I2C workqueue which is asynchronous with FC control loop, +fetching the latest mixing result and write them to PCA9685 at its scheduling ticks. -Воно може виконувати повний вихід 12 біт у режимі циклу керування, а також може виводити цінний ширину імпульсу -що може бути прийнято більшістю ESCs та серводвигунами. +It can do full 12bits output as duty-cycle mode, while also able to output precious pulse width +that can be accepted by most ESCs and servos. ### Приклади -Зазвичай починається з: +It is typically started with: ``` pca9685_pwm_out start -a 0x40 -b 1 ``` - - -### Використання +### Usage {#pca9685_pwm_out_usage} ``` pca9685_pwm_out [arguments...] @@ -1087,11 +963,9 @@ Source: [drivers/power_monitor/pm_selector_auterion](https://github.com/PX4/PX4- ### Опис -Драйвер для запуску та автоматичного виявлення різних датчиків потужності. +Driver for starting and auto-detecting different power monitors. - - -### Використання +### Usage {#pm_selector_auterion_usage} ``` pm_selector_auterion [arguments...] @@ -1107,9 +981,7 @@ pm_selector_auterion [arguments...] Source: [drivers/optical_flow/pmw3901](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/pmw3901) - - -### Використання +### Usage {#pmw3901_usage} ``` pmw3901 [arguments...] @@ -1137,11 +1009,9 @@ Source: [drivers/pps_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src ### Опис -Це реалізує захоплення інформації PPS з модуля GNSS та розраховує відхилення між PPS та годинником реального часу. +This implements capturing PPS information from the GNSS module and calculates the drift between PPS and Real-time clock. - - -### Використання +### Usage {#pps_capture_usage} ``` pps_capture [arguments...] @@ -1159,13 +1029,11 @@ Source: [drivers/pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main/src/dri ### Опис -Цей модуль відповідає за виведення пінів. Для плат без окремого IO-чіпа -(наприклад, Pixracer), використовуються головні канали. На платах з IO-чіпом (наприклад, Pixhawk) використовуються AUX-канали, а -для основних використовується драйвер px4io. +This module is responsible for driving the output pins. For boards without a separate IO chip +(eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the +px4io driver is used for main ones. - - -### Використання +### Usage {#pwm_out_usage} ``` pwm_out [arguments...] @@ -1183,17 +1051,15 @@ Source: [modules/simulation/pwm_out_sim](https://github.com/PX4/PX4-Autopilot/tr ### Опис -Драйвер для імітованих вихідних сигналів ШІМ. +Driver for simulated PWM outputs. Its only function is to take `actuator_control` uORB messages, mix them with any loaded mixer and output the result to the `actuator_output` uORB topic. -Воно використовується в SITL та HITL. +It is used in SITL and HITL. - - -### Використання +### Usage {#pwm_out_sim_usage} ``` pwm_out_sim [arguments...] @@ -1211,9 +1077,7 @@ pwm_out_sim [arguments...] Source: [drivers/optical_flow/px4flow](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/px4flow) - - -### Використання +### Usage {#px4flow_usage} ``` px4flow [arguments...] @@ -1239,11 +1103,9 @@ Source: [drivers/px4io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drive ### Опис -Драйвер виводу, що зв'язується з вводовим ко-процесором. +Output driver communicating with the IO co-processor. - - -### Використання +### Usage {#px4io_usage} ``` px4io [arguments...] @@ -1277,46 +1139,11 @@ px4io [arguments...] status print status info ``` -## rc_input - -Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) - -### Опис - -Цей модуль робить аналіз введення RC та автоматичний вибір методу. Підтримувані методи: - -- PPM -- SBUS -- DSM -- SUMD -- ST24 -- TBS Crossfire (CRSF) - - - -### Використання - -``` -rc_input [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` - ## rgbled Source: [drivers/lights/rgbled_ncp5623c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_ncp5623c) - - -### Використання +### Usage {#rgbled_usage} ``` rgbled [arguments...] @@ -1342,9 +1169,7 @@ rgbled [arguments...] Source: [drivers/lights/rgbled_is31fl3195](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_is31fl3195) - - -### Використання +### Usage {#rgbled_is31fl3195_usage} ``` rgbled_is31fl3195 [arguments...] @@ -1378,11 +1203,9 @@ Driver for [LP5562](https://www.ti.com/product/LP5562) LED driver connected via This used in some GPS modules by Holybro for [PX4 status notification](../getting_started/led_meanings.md) -Водій включений за замовчуванням у вбудованому програмному забезпеченні (ключ KConfig DRIVERS_LIGHTS_RGBLED_LP5562) і завжди увімкнено. +The driver is included by default in firmware (KConfig key DRIVERS_LIGHTS_RGBLED_LP5562) and is always enabled. - - -### Використання +### Usage {#rgbled_lp5562_usage} ``` rgbled_lp5562 [arguments...] @@ -1411,21 +1234,19 @@ Source: [drivers/roboclaw](https://github.com/PX4/PX4-Autopilot/tree/main/src/dr ### Опис This driver communicates over UART with the [Roboclaw motor driver](https://www.basicmicro.com/motor-controller). -Вона виконує дві задачі: +It performs two tasks: -- Контролюйте двигуни на основі інтерфейсу виведення. +- Control the motors based on the OutputModuleInterface. - Read the wheel encoders and publish the raw data in the `wheel_encoders` uORB topic -Для використання цього драйвера Roboclaw повинен бути переведений у режим Packet Serial (див. документацію за посиланням), а -UART-порт вашого контролера польоту повинен бути підключений до Roboclaw, як показано в документації. +In order to use this driver, the Roboclaw should be put into Packet Serial mode (see the linked documentation), and +your flight controller's UART port should be connected to the Roboclaw as shown in the documentation. The driver needs to be enabled using the parameter `RBCLW_SER_CFG`, the baudrate needs to be set correctly and the address `RBCLW_ADDRESS` needs to match the ESC configuration. The command to start this driver is: `$ roboclaw start ` - - -### Використання +### Usage {#roboclaw_usage} ``` roboclaw [arguments...] @@ -1441,9 +1262,7 @@ roboclaw [arguments...] Source: [drivers/rpm_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm_capture) - - -### Використання +### Usage {#rpm_capture_usage} ``` rpm_capture [arguments...] @@ -1461,12 +1280,10 @@ Source: [drivers/safety_button](https://github.com/PX4/PX4-Autopilot/tree/main/s ### Опис -Цей модуль відповідає за кнопку безпеки. -Натискання кнопки безпеки 3 рази швидко спричинить запит на синхронізацію GCS. +This module is responsible for the safety button. +Pressing the safety button 3 times quickly will trigger a GCS pairing request. - - -### Використання +### Usage {#safety_button_usage} ``` safety_button [arguments...] @@ -1478,30 +1295,6 @@ safety_button [arguments...] status print status info ``` -## sbus_rc - -Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) - -### Опис - -This module does SBUS RC input parsing. - - - -### Використання - -``` -sbus_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## septentrio Source: [drivers/gnss/septentrio](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gnss/septentrio) @@ -1535,9 +1328,7 @@ Perform warm reset of the receivers: gps reset warm ``` - - -### Використання +### Usage {#septentrio_usage} ``` septentrio [arguments...] @@ -1566,39 +1357,37 @@ Source: [drivers/hygrometer/sht3x](https://github.com/PX4/PX4-Autopilot/tree/mai ### Опис -Драйвер датчика температури і вологості SHT3x від Senserion. +SHT3x Temperature and Humidity Sensor Driver by Senserion. ### Приклади -Приклад використання CLI: +CLI usage example: ``` sht3x start -X ``` -Запустіть драйвер датчика на зовнішньому шині +Start the sensor driver on the external bus ``` sht3x status ``` -Статус драйвера друку +Print driver status ``` sht3x values ``` -Друкувати останні виміряні значення +Print last measured values ``` sht3x reset ``` -Ініціалізувати датчик, скинути прапорці +Reinitialize senzor, reset flags - - -### Використання +### Usage {#sht3x_usage} ``` sht3x [arguments...] @@ -1629,23 +1418,23 @@ Source: [drivers/tap_esc](https://github.com/PX4/PX4-Autopilot/tree/main/src/dri ### Опис -Цей модуль керує апаратним забезпеченням TAP_ESC через UART. Він слухає теми управління дією, робить змішування та записує вихідні ШІМ сигнали. +This module controls the TAP_ESC hardware via UART. It listens on the +actuator_controls topics, does the mixing and writes the PWM outputs. ### Імплементація -На даний момент модуль реалізований лише у вигляді версії з потоками, що означає, що він працює у власному потоці, а не в черзі завдань. +Currently the module is implemented as a threaded version only, meaning that it +runs in its own thread instead of on the work queue. -### Приклад +### Example -Модуль зазвичай починається з: +The module is typically started with: ``` tap_esc start -d /dev/ttyS2 -n <1-8> ``` - - -### Використання +### Usage {#tap_esc_usage} ``` tap_esc [arguments...] @@ -1663,11 +1452,9 @@ Source: [drivers/tone_alarm](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### Опис -Цей модуль відповідає за сигнал тривоги. +This module is responsible for the tone alarm. - - -### Використання +### Usage {#tone_alarm_usage} ``` tone_alarm [arguments...] @@ -1685,20 +1472,18 @@ Source: [drivers/uwb/uwb_sr150](https://github.com/PX4/PX4-Autopilot/tree/main/s ### Опис -Драйвер для системи позиціонування NXP UWB_SR150 UWB. This driver publishes a `uwb_distance` message +Driver for NXP UWB_SR150 UWB positioning system. This driver publishes a `uwb_distance` message whenever the UWB_SR150 has a position measurement available. -### Приклад +### Example -Запустіть драйвер з вказаним пристроєм: +Start the driver with a given device: ``` uwb start -d /dev/ttyS2 ``` - - -### Використання +### Usage {#uwb_usage} ``` uwb [arguments...] @@ -1718,9 +1503,7 @@ uwb [arguments...] Source: [drivers/actuators/vertiq_io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/actuators/vertiq_io) - - -### Використання +### Usage {#vertiq_io_usage} ``` vertiq_io [arguments...] @@ -1739,13 +1522,11 @@ Source: [drivers/voxl2_io](https://github.com/PX4/PX4-Autopilot/tree/main/src/dr ### Опис -Цей модуль відповідає за виведення пінів. Для плат без окремого IO-чіпа -(наприклад, Pixracer), використовуються головні канали. На платах з IO-чіпом (наприклад, Pixhawk) використовуються AUX-канали, а -для основних використовується драйвер px4io. +This module is responsible for driving the output pins. For boards without a separate IO chip +(eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the +px4io driver is used for main ones. - - -### Використання +### Usage {#voxl2_io_usage} ``` voxl2_io [arguments...] @@ -1771,23 +1552,21 @@ Source: [drivers/actuators/voxl_esc](https://github.com/PX4/PX4-Autopilot/tree/m ### Опис -Цей модуль відповідає за кнопку безпеки... +This module is responsible for... ### Імплементація -За замовчуванням модуль працює в черзі роботи з зворотнім викликом за темою управління актуаторами uORB. +By default the module runs on a work queue with a callback on the uORB actuator_controls topic. ### Приклади -Зазвичай починається з: +It is typically started with: ``` todo ``` - - -### Використання +### Usage {#voxl_esc_usage} ``` voxl_esc [arguments...] @@ -1834,9 +1613,7 @@ voxl_esc [arguments...] Source: [drivers/power_monitor/voxlpm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/voxlpm) - - -### Використання +### Usage {#voxlpm_usage} ``` voxlpm [arguments...] @@ -1866,9 +1643,7 @@ Source: [modules/zenoh](https://github.com/PX4/PX4-Autopilot/tree/main/src/modul Zenoh demo bridge - - -### Використання +### Usage {#zenoh_usage} ``` zenoh [arguments...] diff --git a/docs/uk/modules/modules_driver_airspeed_sensor.md b/docs/uk/modules/modules_driver_airspeed_sensor.md index b79118e323..b8a1c7a92d 100644 --- a/docs/uk/modules/modules_driver_airspeed_sensor.md +++ b/docs/uk/modules/modules_driver_airspeed_sensor.md @@ -13,9 +13,7 @@ TE підключається через I2C. or in default.px4board with adding the line: "CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y" It can be enabled with the "SENS_EN_ASP5033" parameter set to 1. - - -### Використання +### Usage {#asp5033_usage} ``` asp5033 [arguments...] @@ -39,9 +37,7 @@ asp5033 [arguments...] Source: [drivers/differential_pressure/auav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/auav) - - -### Використання +### Usage {#auav_usage} ``` auav [arguments...] @@ -67,9 +63,7 @@ auav [arguments...] Source: [drivers/differential_pressure/ets](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ets) - - -### Використання +### Usage {#ets_airspeed_usage} ``` ets_airspeed [arguments...] @@ -93,9 +87,7 @@ ets_airspeed [arguments...] Source: [drivers/differential_pressure/ms4515](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4515) - - -### Використання +### Usage {#ms4515_usage} ``` ms4515 [arguments...] @@ -119,9 +111,7 @@ ms4515 [arguments...] Source: [drivers/differential_pressure/ms4525do](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4525do) - - -### Використання +### Usage {#ms4525do_usage} ``` ms4525do [arguments...] @@ -145,9 +135,7 @@ ms4525do [arguments...] Source: [drivers/differential_pressure/ms5525dso](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms5525dso) - - -### Використання +### Usage {#ms5525dso_usage} ``` ms5525dso [arguments...] @@ -171,9 +159,7 @@ ms5525dso [arguments...] Source: [drivers/differential_pressure/sdp3x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/sdp3x) - - -### Використання +### Usage {#sdp3x_usage} ``` sdp3x [arguments...] diff --git a/docs/uk/modules/modules_driver_baro.md b/docs/uk/modules/modules_driver_baro.md index ebb42a90ee..8d2a83f4f3 100644 --- a/docs/uk/modules/modules_driver_baro.md +++ b/docs/uk/modules/modules_driver_baro.md @@ -4,9 +4,7 @@ Source: [drivers/barometer/bmp280](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp280) - - -### Використання +### Usage {#bmp280_usage} ``` bmp280 [arguments...] @@ -42,9 +40,7 @@ bmp280 [arguments...] Source: [drivers/barometer/bmp388](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp388) - - -### Використання +### Usage {#bmp388_usage} ``` bmp388 [arguments...] @@ -72,9 +68,7 @@ bmp388 [arguments...] Source: [drivers/barometer/bmp581](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp581) - - -### Використання +### Usage {#bmp581_usage} ``` bmp581 [arguments...] @@ -102,9 +96,7 @@ bmp581 [arguments...] Source: [drivers/barometer/dps310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/dps310) - - -### Використання +### Usage {#dps310_usage} ``` dps310 [arguments...] @@ -140,9 +132,7 @@ dps310 [arguments...] Source: [drivers/barometer/invensense/icp101xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp101xx) - - -### Використання +### Usage {#icp101xx_usage} ``` icp101xx [arguments...] @@ -166,9 +156,7 @@ icp101xx [arguments...] Source: [drivers/barometer/invensense/icp201xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp201xx) - - -### Використання +### Usage {#icp201xx_usage} ``` icp201xx [arguments...] @@ -192,9 +180,7 @@ icp201xx [arguments...] Source: [drivers/barometer/lps22hb](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps22hb) - - -### Використання +### Usage {#lps22hb_usage} ``` lps22hb [arguments...] @@ -220,9 +206,7 @@ lps22hb [arguments...] Source: [drivers/barometer/lps25h](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps25h) - - -### Використання +### Usage {#lps25h_usage} ``` lps25h [arguments...] @@ -248,9 +232,7 @@ lps25h [arguments...] Source: [drivers/barometer/lps33hw](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps33hw) - - -### Використання +### Usage {#lps33hw_usage} ``` lps33hw [arguments...] @@ -279,9 +261,7 @@ lps33hw [arguments...] Source: [drivers/barometer/maiertek/mpc2520](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/maiertek/mpc2520) - - -### Використання +### Usage {#mpc2520_usage} ``` mpc2520 [arguments...] @@ -305,9 +285,7 @@ mpc2520 [arguments...] Source: [drivers/barometer/mpl3115a2](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/mpl3115a2) - - -### Використання +### Usage {#mpl3115a2_usage} ``` mpl3115a2 [arguments...] @@ -331,9 +309,7 @@ mpl3115a2 [arguments...] Source: [drivers/barometer/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - - -### Використання +### Usage {#ms5611_usage} ``` ms5611 [arguments...] @@ -369,9 +345,7 @@ ms5611 [arguments...] Source: [drivers/barometer/ms5837](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5837) - - -### Використання +### Usage {#ms5837_usage} ``` ms5837 [arguments...] @@ -393,9 +367,7 @@ ms5837 [arguments...] Source: [drivers/barometer/goertek/spa06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spa06) - - -### Використання +### Usage {#spa06_usage} ``` spa06 [arguments...] @@ -431,9 +403,7 @@ spa06 [arguments...] Source: [drivers/barometer/goertek/spl06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spl06) - - -### Використання +### Usage {#spl06_usage} ``` spl06 [arguments...] diff --git a/docs/uk/modules/modules_driver_camera.md b/docs/uk/modules/modules_driver_camera.md index bc558b51a6..b7afb329ba 100644 --- a/docs/uk/modules/modules_driver_camera.md +++ b/docs/uk/modules/modules_driver_camera.md @@ -34,9 +34,7 @@ The driver is configured using [Camera Trigger parameters](../advanced_config/pa [Setup/usage information](../camera/index.md). - - -### Використання +### Usage {#camera_trigger_usage} ``` camera_trigger [arguments...] diff --git a/docs/uk/modules/modules_driver_distance_sensor.md b/docs/uk/modules/modules_driver_distance_sensor.md index 830d0bd8c1..2901b4afc1 100644 --- a/docs/uk/modules/modules_driver_distance_sensor.md +++ b/docs/uk/modules/modules_driver_distance_sensor.md @@ -10,7 +10,7 @@ Source: [drivers/distance_sensor/broadcom/afbrs50](https://github.com/PX4/PX4-Au ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` afbrs50 start @@ -22,9 +22,7 @@ Stop driver afbrs50 stop ``` - - -### Використання +### Usage {#afbrs50_usage} ``` afbrs50 [arguments...] @@ -43,9 +41,7 @@ afbrs50 [arguments...] Source: [drivers/distance_sensor/gy_us42](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/gy_us42) - - -### Використання +### Usage {#gy_us42_usage} ``` gy_us42 [arguments...] @@ -71,15 +67,15 @@ Source: [drivers/distance_sensor/leddar_one](https://github.com/PX4/PX4-Autopilo ### Опис -Драйвер послідовної шини для LiDAR LeddarOne. +Serial bus driver for the LeddarOne LiDAR. -Більшість плат налаштовано на ввімкнення/запуск драйвера на вказаному UART за допомогою параметра SENS_LEDDAR1_CFG. +Most boards are configured to enable/start the driver on a specified UART using the SENS_LEDDAR1_CFG parameter. -Інформація про налаштування/використання: https://docs.px4.io/main/en/sensor/leddar_one.html +Setup/usage information: https://docs.px4.io/main/en/sensor/leddar_one.html ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` leddar_one start -d /dev/ttyS1 @@ -91,9 +87,7 @@ Stop driver leddar_one stop ``` - - -### Використання +### Usage {#leddar_one_usage} ``` leddar_one [arguments...] @@ -112,13 +106,11 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### Опис -Драйвер шини I2C для LIDAR-далекомірів Lightware серії SFxx: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. -Інформація про налаштування/використання: https://docs.px4.io/main/en/sensor/sfxx_lidar.html +Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html - - -### Використання +### Usage {#lightware_laser_i2c_usage} ``` lightware_laser_i2c [arguments...] @@ -146,15 +138,15 @@ Source: [drivers/distance_sensor/lightware_laser_serial](https://github.com/PX4/ ### Опис -Драйвер послідовної шини для лазерних далекомірів LightWare SF02/F, SF10/a, SF10/b, SF10/c, SF11/c. +Serial bus driver for the LightWare SF02/F, SF10/a, SF10/b, SF10/c, SF11/c Laser rangefinders. -Більшість плат налаштовано на увімкнення/запуск драйвера на вказаному UART за допомогою параметра SENS_SF0X_CFG. +Most boards are configured to enable/start the driver on a specified UART using the SENS_SF0X_CFG parameter. -Інформація про налаштування/використання: https://docs.px4.io/main/en/sensor/sfxx_lidar.html +Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` lightware_laser_serial start -d /dev/ttyS1 @@ -166,9 +158,7 @@ Stop driver lightware_laser_serial stop ``` - - -### Використання +### Usage {#lightware_laser_serial_usage} ``` lightware_laser_serial [arguments...] @@ -187,11 +177,11 @@ Source: [drivers/distance_sensor/lightware_sf45_serial](https://github.com/PX4/P ### Опис -Драйвер послідовної шини для лазерного далекоміра Lightware SF45/b. +Serial bus driver for the Lightware SF45/b Laser rangefinder. ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` lightware_sf45_serial start -d /dev/ttyS1 @@ -203,9 +193,7 @@ Stop driver lightware_sf45_serial stop ``` - - -### Використання +### Usage {#lightware_sf45_serial_usage} ``` lightware_sf45_serial [arguments...] @@ -224,13 +212,11 @@ Source: [drivers/distance_sensor/ll40ls_pwm](https://github.com/PX4/PX4-Autopilo PWM driver for LidarLite rangefinders. -Датчик/драйвер має бути увімкнений за допомогою параметра SENS_EN_LL40LS. +The sensor/driver must be enabled using the parameter SENS_EN_LL40LS. -Інформація про налаштування/використання: https://docs.px4.io/main/en/sensor/lidar_lite.html +Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html - - -### Використання +### Usage {#ll40ls_usage} ``` ll40ls [arguments...] @@ -248,9 +234,7 @@ ll40ls [arguments...] Source: [drivers/distance_sensor/mappydot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mappydot) - - -### Використання +### Usage {#mappydot_usage} ``` mappydot [arguments...] @@ -272,9 +256,7 @@ mappydot [arguments...] Source: [drivers/distance_sensor/mb12xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mb12xx) - - -### Використання +### Usage {#mb12xx_usage} ``` mb12xx [arguments...] @@ -302,19 +284,17 @@ Source: [drivers/distance_sensor/pga460](https://github.com/PX4/PX4-Autopilot/tr ### Опис -Драйвер ультразвукового далекоміра, який здійснює зв'язок з пристроєм і публікує відстань через uORB. +Ultrasonic range finder driver that handles the communication with the device and publishes the distance via uORB. ### Імплементація -Цей драйвер реалізовано як завдання NuttX. Ця реалізація була обрана через необхідність опитування на повідомлення -через UART, що не підтримується у work_queue. Цей драйвер безперервно вимірює дальність коли він -працює. На рівні драйверів реалізовано простий алгоритм виявлення хибних показань, що має на меті покращити -якість даних, що публікуються. Драйвер взагалі не публікуватиме дані, якщо вважатиме, що дані датчика -недійсними або нестабільними. +This driver is implemented as a NuttX task. This Implementation was chosen due to the need for polling on a message +via UART, which is not supported in the work_queue. This driver continuously takes range measurements while it is +running. A simple algorithm to detect false readings is implemented at the driver levelin an attemptto improve +the quality of data that is being published. The driver will not publish data at all if it deems the sensor data +to be invalid or unstable. - - -### Використання +### Usage {#pga460_usage} ``` pga460 [arguments...] @@ -333,9 +313,7 @@ pga460 [arguments...] Source: [drivers/distance_sensor/srf02](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/srf02) - - -### Використання +### Usage {#srf02_usage} ``` srf02 [arguments...] @@ -363,13 +341,11 @@ Source: [drivers/distance_sensor/srf05](https://github.com/PX4/PX4-Autopilot/tre ### Опис -Драйвер для далекомірів HY-SRF05 / HC-SR05 та HC-SR04. +Driver for HY-SRF05 / HC-SR05 and HC-SR04 rangefinders. -Датчик/драйвер потрібно увімкнути за допомогою параметра SENS_EN_HXSRX0X. +The sensor/driver must be enabled using the parameter SENS_EN_HXSRX0X. - - -### Використання +### Usage {#srf05_usage} ``` srf05 [arguments...] @@ -393,15 +369,13 @@ Source: [drivers/distance_sensor/teraranger](https://github.com/PX4/PX4-Autopilo ### Опис -Драйвер шини I2C для далекомірів TeraRanger. +I2C bus driver for TeraRanger rangefinders. -Датчик/драйвер має бути увімкнений за допомогою параметра SENS_EN_TRANGER. +The sensor/driver must be enabled using the parameter SENS_EN_TRANGER. -Інформація про налаштування/використання: https://docs.px4.io/main/en/sensor/rangefinders.html#teraranger-rangefinders +Setup/usage information: https://docs.px4.io/main/en/sensor/rangefinders.html#teraranger-rangefinders - - -### Використання +### Usage {#teraranger_usage} ``` teraranger [arguments...] @@ -427,9 +401,7 @@ teraranger [arguments...] Source: [drivers/distance_sensor/tf02pro](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/tf02pro) - - -### Використання +### Usage {#tf02pro_usage} ``` tf02pro [arguments...] @@ -457,15 +429,15 @@ Source: [drivers/distance_sensor/tfmini](https://github.com/PX4/PX4-Autopilot/tr ### Опис -Серійний драйвер шини для Benewake TFmini LiDAR. +Serial bus driver for the Benewake TFmini LiDAR. -Більшість плат налаштовано на ввімкнення/вимкнення драйвера на вказаному UART за допомогою параметра SENS_TFMINI_CFG. +Most boards are configured to enable/start the driver on a specified UART using the SENS_TFMINI_CFG parameter. -Інформація про налаштування/використання: https://docs.px4.io/main/en/sensor/tfmini.html +Setup/usage information: https://docs.px4.io/main/en/sensor/tfmini.html ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` tfmini start -d /dev/ttyS1 @@ -477,9 +449,7 @@ Stop driver tfmini stop ``` - - -### Використання +### Usage {#tfmini_usage} ``` tfmini [arguments...] @@ -502,13 +472,13 @@ Source: [drivers/distance_sensor/ulanding_radar](https://github.com/PX4/PX4-Auto ### Опис -Серійний драйвер шини для радара Aerotenna uLanding. +Serial bus driver for the Aerotenna uLanding radar. Setup/usage information: https://docs.px4.io/main/en/sensor/ulanding_radar.html ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` ulanding_radar start -d /dev/ttyS1 @@ -520,9 +490,7 @@ Stop driver ulanding_radar stop ``` - - -### Використання +### Usage {#ulanding_radar_usage} ``` ulanding_radar [arguments...] @@ -540,9 +508,7 @@ ulanding_radar [arguments...] Source: [drivers/distance_sensor/vl53l0x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l0x) - - -### Використання +### Usage {#vl53l0x_usage} ``` vl53l0x [arguments...] @@ -568,9 +534,7 @@ vl53l0x [arguments...] Source: [drivers/distance_sensor/vl53l1x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l1x) - - -### Використання +### Usage {#vl53l1x_usage} ``` vl53l1x [arguments...] diff --git a/docs/uk/modules/modules_driver_imu.md b/docs/uk/modules/modules_driver_imu.md index e3a738693a..ed5da8d8ea 100644 --- a/docs/uk/modules/modules_driver_imu.md +++ b/docs/uk/modules/modules_driver_imu.md @@ -4,9 +4,7 @@ Source: [drivers/imu/analog_devices/adis16448](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16448) - - -### Використання +### Usage {#adis16448_usage} ``` adis16448 [arguments...] @@ -32,9 +30,7 @@ adis16448 [arguments...] Source: [drivers/imu/analog_devices/adis16470](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16470) - - -### Використання +### Usage {#adis16470_usage} ``` adis16470 [arguments...] @@ -60,9 +56,7 @@ adis16470 [arguments...] Source: [drivers/imu/analog_devices/adis16477](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16477) - - -### Використання +### Usage {#adis16477_usage} ``` adis16477 [arguments...] @@ -88,9 +82,7 @@ adis16477 [arguments...] Source: [drivers/imu/analog_devices/adis16497](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16497) - - -### Використання +### Usage {#adis16497_usage} ``` adis16497 [arguments...] @@ -116,9 +108,7 @@ adis16497 [arguments...] Source: [drivers/imu/analog_devices/adis16507](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16507) - - -### Використання +### Usage {#adis16507_usage} ``` adis16507 [arguments...] @@ -144,9 +134,7 @@ adis16507 [arguments...] Source: [drivers/imu/bosch/bmi055](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi055) - - -### Використання +### Usage {#bmi055_usage} ``` bmi055 [arguments...] @@ -174,9 +162,7 @@ bmi055 [arguments...] Source: [drivers/imu/bosch/bmi085](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi085) - - -### Використання +### Usage {#bmi085_usage} ``` bmi085 [arguments...] @@ -204,9 +190,7 @@ bmi085 [arguments...] Source: [drivers/imu/bosch/bmi088](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088) - - -### Використання +### Usage {#bmi088_usage} ``` bmi088 [arguments...] @@ -234,9 +218,7 @@ bmi088 [arguments...] Source: [drivers/imu/bosch/bmi088_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088_i2c) - - -### Використання +### Usage {#bmi088_i2c_usage} ``` bmi088_i2c [arguments...] @@ -264,9 +246,7 @@ bmi088_i2c [arguments...] Source: [drivers/imu/bosch/bmi270](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi270) - - -### Використання +### Usage {#bmi270_usage} ``` bmi270 [arguments...] @@ -292,9 +272,7 @@ bmi270 [arguments...] Source: [drivers/imu/nxp/fxas21002c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxas21002c) - - -### Використання +### Usage {#fxas21002c_usage} ``` fxas21002c [arguments...] @@ -328,9 +306,7 @@ fxas21002c [arguments...] Source: [drivers/imu/nxp/fxos8701cq](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxos8701cq) - - -### Використання +### Usage {#fxos8701cq_usage} ``` fxos8701cq [arguments...] @@ -364,9 +340,7 @@ fxos8701cq [arguments...] Source: [drivers/imu/invensense/iam20680hp](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iam20680hp) - - -### Використання +### Usage {#iam20680hp_usage} ``` iam20680hp [arguments...] @@ -392,9 +366,7 @@ iam20680hp [arguments...] Source: [drivers/imu/invensense/icm20602](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20602) - - -### Використання +### Usage {#icm20602_usage} ``` icm20602 [arguments...] @@ -420,9 +392,7 @@ icm20602 [arguments...] Source: [drivers/imu/invensense/icm20608g](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20608g) - - -### Використання +### Usage {#icm20608g_usage} ``` icm20608g [arguments...] @@ -448,9 +418,7 @@ icm20608g [arguments...] Source: [drivers/imu/invensense/icm20649](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20649) - - -### Використання +### Usage {#icm20649_usage} ``` icm20649 [arguments...] @@ -476,9 +444,7 @@ icm20649 [arguments...] Source: [drivers/imu/invensense/icm20689](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20689) - - -### Використання +### Usage {#icm20689_usage} ``` icm20689 [arguments...] @@ -504,9 +470,7 @@ icm20689 [arguments...] Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - - -### Використання +### Usage {#icm20948_usage} ``` icm20948 [arguments...] @@ -533,9 +497,7 @@ icm20948 [arguments...] Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - - -### Використання +### Usage {#icm20948_i2c_passthrough_usage} ``` icm20948_i2c_passthrough [arguments...] @@ -559,9 +521,7 @@ icm20948_i2c_passthrough [arguments...] Source: [drivers/imu/invensense/icm40609d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm40609d) - - -### Використання +### Usage {#icm40609d_usage} ``` icm40609d [arguments...] @@ -587,9 +547,7 @@ icm40609d [arguments...] Source: [drivers/imu/invensense/icm42605](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42605) - - -### Використання +### Usage {#icm42605_usage} ``` icm42605 [arguments...] @@ -615,9 +573,7 @@ icm42605 [arguments...] Source: [drivers/imu/invensense/icm42670p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42670p) - - -### Використання +### Usage {#icm42670p_usage} ``` icm42670p [arguments...] @@ -643,9 +599,7 @@ icm42670p [arguments...] Source: [drivers/imu/invensense/icm42688p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42688p) - - -### Використання +### Usage {#icm42688p_usage} ``` icm42688p [arguments...] @@ -674,9 +628,7 @@ icm42688p [arguments...] Source: [drivers/imu/invensense/icm45686](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm45686) - - -### Використання +### Usage {#icm45686_usage} ``` icm45686 [arguments...] @@ -704,9 +656,7 @@ icm45686 [arguments...] Source: [drivers/imu/invensense/iim42652](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42652) - - -### Використання +### Usage {#iim42652_usage} ``` iim42652 [arguments...] @@ -734,9 +684,7 @@ iim42652 [arguments...] Source: [drivers/imu/invensense/iim42653](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42653) - - -### Використання +### Usage {#iim42653_usage} ``` iim42653 [arguments...] @@ -764,9 +712,7 @@ iim42653 [arguments...] Source: [drivers/imu/st/l3gd20](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/l3gd20) - - -### Використання +### Usage {#l3gd20_usage} ``` l3gd20 [arguments...] @@ -796,9 +742,7 @@ l3gd20 [arguments...] Source: [drivers/imu/st/lsm303d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm303d) - - -### Використання +### Usage {#lsm303d_usage} ``` lsm303d [arguments...] @@ -824,9 +768,7 @@ lsm303d [arguments...] Source: [drivers/imu/st/lsm9ds1](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm9ds1) - - -### Використання +### Usage {#lsm9ds1_usage} ``` lsm9ds1 [arguments...] @@ -852,9 +794,7 @@ lsm9ds1 [arguments...] Source: [drivers/imu/invensense/mpu6000](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6000) - - -### Використання +### Usage {#mpu6000_usage} ``` mpu6000 [arguments...] @@ -880,9 +820,7 @@ mpu6000 [arguments...] Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - - -### Використання +### Usage {#mpu9250_usage} ``` mpu9250 [arguments...] @@ -909,9 +847,7 @@ mpu9250 [arguments...] Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - - -### Використання +### Usage {#mpu9250_i2c_usage} ``` mpu9250_i2c [arguments...] @@ -937,9 +873,7 @@ mpu9250_i2c [arguments...] Source: [drivers/imu/invensense/mpu6500](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6500) - - -### Використання +### Usage {#mpu9520_usage} ``` mpu9520 [arguments...] @@ -965,9 +899,7 @@ mpu9520 [arguments...] Source: [drivers/imu/murata/sch16t](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/murata/sch16t) - - -### Використання +### Usage {#sch16t_usage} ``` sch16t [arguments...] diff --git a/docs/uk/modules/modules_driver_ins.md b/docs/uk/modules/modules_driver_ins.md index 2ad7c55bb9..0ada484050 100644 --- a/docs/uk/modules/modules_driver_ins.md +++ b/docs/uk/modules/modules_driver_ins.md @@ -14,7 +14,7 @@ Source: [drivers/ins/vectornav](https://github.com/PX4/PX4-Autopilot/tree/main/s ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` vectornav start -d /dev/ttyS1 @@ -26,9 +26,7 @@ Stop driver vectornav stop ``` - - -### Використання +### Usage {#vectornav_usage} ``` vectornav [arguments...] diff --git a/docs/uk/modules/modules_driver_magnetometer.md b/docs/uk/modules/modules_driver_magnetometer.md index cb3b36031e..8d527cfa4e 100644 --- a/docs/uk/modules/modules_driver_magnetometer.md +++ b/docs/uk/modules/modules_driver_magnetometer.md @@ -4,9 +4,7 @@ Source: [drivers/magnetometer/akm/ak09916](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak09916) - - -### Використання +### Usage {#ak09916_usage} ``` ak09916 [arguments...] @@ -32,9 +30,7 @@ ak09916 [arguments...] Source: [drivers/magnetometer/akm/ak8963](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak8963) - - -### Використання +### Usage {#ak8963_usage} ``` ak8963 [arguments...] @@ -60,9 +56,7 @@ ak8963 [arguments...] Source: [drivers/magnetometer/bosch/bmm150](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm150) - - -### Використання +### Usage {#bmm150_usage} ``` bmm150 [arguments...] @@ -88,9 +82,7 @@ bmm150 [arguments...] Source: [drivers/magnetometer/bosch/bmm350](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm350) - - -### Використання +### Usage {#bmm350_usage} ``` bmm350 [arguments...] @@ -116,9 +108,7 @@ bmm350 [arguments...] Source: [drivers/magnetometer/hmc5883](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/hmc5883) - - -### Використання +### Usage {#hmc5883_usage} ``` hmc5883 [arguments...] @@ -147,9 +137,7 @@ hmc5883 [arguments...] Source: [drivers/magnetometer/st/iis2mdc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/st/iis2mdc) - - -### Використання +### Usage {#iis2mdc_usage} ``` iis2mdc [arguments...] @@ -173,9 +161,7 @@ iis2mdc [arguments...] Source: [drivers/magnetometer/isentek/ist8308](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8308) - - -### Використання +### Usage {#ist8308_usage} ``` ist8308 [arguments...] @@ -201,9 +187,7 @@ ist8308 [arguments...] Source: [drivers/magnetometer/isentek/ist8310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8310) - - -### Використання +### Usage {#ist8310_usage} ``` ist8310 [arguments...] @@ -229,9 +213,7 @@ ist8310 [arguments...] Source: [drivers/magnetometer/lis3mdl](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lis3mdl) - - -### Використання +### Usage {#lis3mdl_usage} ``` lis3mdl [arguments...] @@ -263,9 +245,7 @@ lis3mdl [arguments...] Source: [drivers/magnetometer/lsm9ds1_mag](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm9ds1_mag) - - -### Використання +### Usage {#lsm9ds1_mag_usage} ``` lsm9ds1_mag [arguments...] @@ -291,9 +271,7 @@ lsm9ds1_mag [arguments...] Source: [drivers/magnetometer/memsic/mmc5983ma](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/memsic/mmc5983ma) - - -### Використання +### Usage {#mmc5983ma_usage} ``` mmc5983ma [arguments...] @@ -325,9 +303,7 @@ mmc5983ma [arguments...] Source: [drivers/magnetometer/qmc5883l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/qmc5883l) - - -### Використання +### Usage {#qmc5883l_usage} ``` qmc5883l [arguments...] @@ -353,9 +329,7 @@ qmc5883l [arguments...] Source: [drivers/magnetometer/rm3100](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/rm3100) - - -### Використання +### Usage {#rm3100_usage} ``` rm3100 [arguments...] @@ -383,9 +357,7 @@ rm3100 [arguments...] Source: [drivers/magnetometer/vtrantech/vcm1193l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/vtrantech/vcm1193l) - - -### Використання +### Usage {#vcm1193l_usage} ``` vcm1193l [arguments...] diff --git a/docs/uk/modules/modules_driver_optical_flow.md b/docs/uk/modules/modules_driver_optical_flow.md index 65eee76928..70a182d3d1 100644 --- a/docs/uk/modules/modules_driver_optical_flow.md +++ b/docs/uk/modules/modules_driver_optical_flow.md @@ -14,7 +14,7 @@ Source: [drivers/optical_flow/thoneflow](https://github.com/PX4/PX4-Autopilot/tr ### Приклади -Спроба запустити драйвер на вказаному послідовному пристрої. +Attempt to start driver on a specified serial device. ``` thoneflow start -d /dev/ttyS1 @@ -26,9 +26,7 @@ Stop driver thoneflow stop ``` - - -### Використання +### Usage {#thoneflow_usage} ``` thoneflow [arguments...] diff --git a/docs/uk/modules/modules_driver_radio_control.md b/docs/uk/modules/modules_driver_radio_control.md new file mode 100644 index 0000000000..473c70c11f --- /dev/null +++ b/docs/uk/modules/modules_driver_radio_control.md @@ -0,0 +1,122 @@ +# Modules Reference: Radio Control (Driver) + +## crsf_rc + +Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) + +### Опис + +This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data + +### Usage {#crsf_rc_usage} + +``` +crsf_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## dsm_rc + +Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) + +### Опис + +This module does Spektrum DSM RC input parsing. + +### Usage {#dsm_rc_usage} + +``` +dsm_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## ghst_rc + +Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) + +### Опис + +This module does Ghost (GHST) RC input parsing. + +### Usage {#ghst_rc_usage} + +``` +ghst_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## rc_input + +Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) + +### Опис + +This module does the RC input parsing and auto-selecting the method. Supported methods are: + +- PPM +- SBUS +- DSM +- SUMD +- ST24 +- TBS Crossfire (CRSF) + +### Usage {#rc_input_usage} + +``` +rc_input [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## sbus_rc + +Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) + +### Опис + +This module does SBUS RC input parsing. + +### Usage {#sbus_rc_usage} + +``` +sbus_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` diff --git a/docs/uk/modules/modules_driver_rpm_sensor.md b/docs/uk/modules/modules_driver_rpm_sensor.md index f014eb0c20..b4d7b95243 100644 --- a/docs/uk/modules/modules_driver_rpm_sensor.md +++ b/docs/uk/modules/modules_driver_rpm_sensor.md @@ -4,9 +4,7 @@ Source: [drivers/rpm/pcf8583](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm/pcf8583) - - -### Використання +### Usage {#pcf8583_usage} ``` pcf8583 [arguments...] diff --git a/docs/uk/modules/modules_driver_transponder.md b/docs/uk/modules/modules_driver_transponder.md index 931cd83cf6..783fb4dfd3 100644 --- a/docs/uk/modules/modules_driver_transponder.md +++ b/docs/uk/modules/modules_driver_transponder.md @@ -24,9 +24,7 @@ Set the Squawk Code $ sagetech_mxs squawk 1200 ``` - - -### Використання +### Usage {#sagetech_mxs_usage} ``` sagetech_mxs [arguments...] diff --git a/docs/uk/modules/modules_estimator.md b/docs/uk/modules/modules_estimator.md index 555d96202b..af7d898ee6 100644 --- a/docs/uk/modules/modules_estimator.md +++ b/docs/uk/modules/modules_estimator.md @@ -8,9 +8,7 @@ Source: [modules/attitude_estimator_q](https://github.com/PX4/PX4-Autopilot/tree Оцінювач висоти q. - - -### Використання +### Usage {#AttitudeEstimatorQ_usage} ``` AttitudeEstimatorQ [arguments...] @@ -34,9 +32,7 @@ Source: [modules/airspeed_selector](https://github.com/PX4/PX4-Autopilot/tree/ma оцінки масштабного коефіцієнта від IAS до CAS, вона запускає кілька оцінювачів вітру а також публікує їх. - - -### Використання +### Usage {#airspeed_estimator_usage} ``` airspeed_estimator [arguments...] @@ -61,9 +57,7 @@ The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.p ekf2 can be started in replay mode (`-r`): in this mode, it does not access the system time, but only uses the timestamps from the sensor topics. - - -### Використання +### Usage {#ekf2_usage} ``` ekf2 [arguments...] @@ -88,9 +82,7 @@ Source: [modules/local_position_estimator](https://github.com/PX4/PX4-Autopilot/ Оцінювач відношення та позиції за допомогою розширеного фільтра Калмана. - - -### Використання +### Usage {#local_position_estimator_usage} ``` local_position_estimator [arguments...] @@ -108,9 +100,7 @@ Source: [modules/mc_hover_thrust_estimator](https://github.com/PX4/PX4-Autopilot ### Опис - - -### Використання +### Usage {#mc_hover_thrust_estimator_usage} ``` mc_hover_thrust_estimator [arguments...] diff --git a/docs/uk/modules/modules_simulation.md b/docs/uk/modules/modules_simulation.md index 39a108a70a..990145fcb6 100644 --- a/docs/uk/modules/modules_simulation.md +++ b/docs/uk/modules/modules_simulation.md @@ -16,9 +16,7 @@ Source: [modules/simulation/simulator_sih](https://github.com/PX4/PX4-Autopilot/ Симулятор реалізує рівняння руху за допомогою матричної алгебри.Використовується кватерніонне представлення для орієнтації.Для інтегрування використовується пряма схема Ейлера.Більшість змінних оголошуються глобальними в файлі .hpp, щоб уникнути переповнення стеку. - - -### Використання +### Usage {#simulator_sih_usage} ``` simulator_sih [arguments...] diff --git a/docs/uk/modules/modules_system.md b/docs/uk/modules/modules_system.md index 723a9a246c..f0f23b9ff7 100644 --- a/docs/uk/modules/modules_system.md +++ b/docs/uk/modules/modules_system.md @@ -6,9 +6,7 @@ Source: [modules/simulation/battery_simulator](https://github.com/PX4/PX4-Autopi ### Опис - - -### Використання +### Usage {#battery_simulator_usage} ``` battery_simulator [arguments...] @@ -26,17 +24,15 @@ Source: [modules/battery_status](https://github.com/PX4/PX4-Autopilot/tree/main/ ### Опис -Надана функціональність включає в себе: +The provided functionality includes: - Read the output from the ADC driver (via ioctl interface) and publish `battery_status`. ### Імплементація -Він запускається у власній темі і проводить опитування на поточну обрану тему гіроскопа. +It runs in its own thread and polls on the currently selected gyro topic. - - -### Використання +### Usage {#battery_status_usage} ``` battery_status [arguments...] @@ -74,9 +70,7 @@ It discards topics from the `camera_trigger` module if camera capture is enabled For the topics that are not discarded it creates a `CameraCapture` topic with the timestamp information from the `CameraTrigger` and position information from the vehicle. - - -### Використання +### Usage {#camera_feedback_usage} ``` camera_feedback [arguments...] @@ -94,14 +88,12 @@ Source: [drivers/cdcacm_autostart](https://github.com/PX4/PX4-Autopilot/tree/mai ### Опис -Цей модуль прослуховує USB і автоматично налаштовує протокол в залежності від отриманих байтів. -Підтримувані протоколи: MAVLink, nsh та ublox послідовний прохід. Якщо параметр SYS_USB_AUTO=2 -модуль буде намагатися запустити mavlink лише тоді, коли буде виявлено USB VBUS. В іншому випадку він буде обертатися -і продовжувати перевіряти VBUS та запускати mavlink, як тільки він виявиться. +This module listens on USB and auto-configures the protocol depending on the bytes received. +The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the parameter SYS_USB_AUTO=2 +the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin +and continue to check for VBUS and start mavlink once it is detected. - - -### Використання +### Usage {#cdcacm_autostart_usage} ``` cdcacm_autostart [arguments...] @@ -119,11 +111,9 @@ Source: [modules/commander](https://github.com/PX4/PX4-Autopilot/tree/main/src/m ### Опис -Модуль командира містить машину станів для перемикання режимів та аварійної поведінки. +The commander module contains the state machine for mode switching and failsafe behavior. - - -### Використання +### Usage {#commander_usage} ``` commander [arguments...] @@ -177,22 +167,20 @@ Source: [modules/dataman](https://github.com/PX4/PX4-Autopilot/tree/main/src/mod ### Опис -Модуль для забезпечення постійного сховища для решти системи у вигляді простої бази даних через C API. +Module to provide persistent storage for the rest of the system in form of a simple database through a C API. Multiple backends are supported depending on the board: -- файл (наприклад, на SD-карті) -- Оперативна пам'ять (очевидно, що вона не є постійною) +- a file (eg. on the SD card) +- RAM (this is obviously not persistent) -Використовується для зберігання структурованих даних різних типів: маршрутні точки місії, стан місії та полігони геозони. -Кожен тип має певний тип і фіксовану максимальну кількість елементів зберігання, щоб забезпечити швидкий випадковий доступ. +It is used to store structured data of different types: mission waypoints, mission state and geofence polygons. +Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible. ### Імплементація -Читання і запис одного елемента завжди атомарні. +Reading and writing a single item is always atomic. - - -### Використання +### Usage {#dataman_usage} ``` dataman [arguments...] @@ -216,20 +204,18 @@ Source: [systemcmds/dmesg](https://github.com/PX4/PX4-Autopilot/tree/main/src/sy ### Опис -Інструмент командного рядка для показу повідомлень консолі завантаження. -Зауважте, що вивід з робочих черг NuttX та syslog не перехоплюється. +Command-line tool to show bootup console messages. +Note that output from NuttX's work queues and syslog are not captured. ### Приклади -Продовжує друкувати всі повідомлення у фоновому режимі: +Keep printing all messages in the background: ``` dmesg -f & ``` - - -### Використання +### Usage {#dmesg_usage} ``` dmesg [arguments...] @@ -243,11 +229,9 @@ Source: [modules/esc_battery](https://github.com/PX4/PX4-Autopilot/tree/main/src ### Опис -Це реалізує використання інформації зі статусу ESC і публікує її як стан батареї. +This implements using information from the ESC status and publish it as battery status. - - -### Використання +### Usage {#esc_battery_usage} ``` esc_battery [arguments...] @@ -265,11 +249,9 @@ Source: [modules/gyro_calibration](https://github.com/PX4/PX4-Autopilot/tree/mai ### Опис -Просте онлайн-калібрування гіроскопа. +Simple online gyroscope calibration. - - -### Використання +### Usage {#gyro_calibration_usage} ``` gyro_calibration [arguments...] @@ -287,9 +269,7 @@ Source: [modules/gyro_fft](https://github.com/PX4/PX4-Autopilot/tree/main/src/mo ### Опис - - -### Використання +### Usage {#gyro_fft_usage} ``` gyro_fft [arguments...] @@ -307,13 +287,11 @@ Source: [drivers/heater](https://github.com/PX4/PX4-Autopilot/tree/main/src/driv ### Опис -Фоновий процес, що періодично запускається в робочій черзі LP для регулювання температури IMU на заданому рівні. +Background process running periodically on the LP work queue to regulate IMU temperature at a setpoint. -Це завдання можна запустити під час завантаження зі скриптів запуску, встановивши SENS_EN_THERMAL, або через CLI. +This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI. - - -### Використання +### Usage {#heater_usage} ``` heater [arguments...] @@ -331,11 +309,9 @@ Source: [systemcmds/i2c_launcher](https://github.com/PX4/PX4-Autopilot/tree/main ### Опис -Демон, який запускає драйвери на основі виявлених пристроїв I2C. +Daemon that starts drivers based on found I2C devices. - - -### Використання +### Usage {#i2c_launcher_usage} ``` i2c_launcher [arguments...] @@ -401,9 +377,7 @@ The architecture is as shown below: - - -### Використання +### Usage {#internal_combustion_engine_control_usage} ``` internal_combustion_engine_control [arguments...] @@ -427,26 +401,25 @@ states, such as commanded thrust, arming state and vehicle motion. ### Імплементація -Кожен тип реалізовано у власному класі зі спільним базовим класом. Базовий клас підтримує стан (landed, -maybe_landed, ground_contact). Кожен можливий стан реалізується в похідних класах. Гістерезис та фіксований -пріоритет кожного внутрішнього стану визначає фактичний стан land_detector. +Every type is implemented in its own class with a common base class. The base class maintains a state (landed, +maybe_landed, ground_contact). Each possible state is implemented in the derived classes. A hysteresis and a fixed +priority of each internal state determines the actual land_detector state. -#### Мультикоптер Land Detector +#### Multicopter Land Detector **ground_contact**: thrust setpoint and velocity in z-direction must be below a defined threshold for time -GROUND_CONTACT_TRIGGER_TIME_US. При виявленні контакту з землею регулятор положення вимикає задане значення тяги -у тілі x та y. +GROUND_CONTACT_TRIGGER_TIME_US. When ground_contact is detected, the position controller turns off the thrust setpoint +in body x and y. **maybe_landed**: it requires ground_contact together with a tighter thrust setpoint threshold and no velocity in the -horizontal direction. Час спрацьовування визначається параметром MAYBE_LAND_TRIGGER_TIME. Коли виявляється maybe_landed, контролер положення встановлює задане значення тяги на нуль. +horizontal direction. The trigger time is defined by MAYBE_LAND_TRIGGER_TIME. When maybe_landed is detected, the +position controller sets the thrust setpoint to zero. **landed**: it requires maybe_landed to be true for time LAND_DETECTOR_TRIGGER_TIME_US. -Модуль періодично запускається у черзі робіт HP. +The module runs periodically on the HP work queue. - - -### Використання +### Usage {#land_detector_usage} ``` land_detector [arguments...] @@ -468,12 +441,10 @@ Source: [modules/load_mon](https://github.com/PX4/PX4-Autopilot/tree/main/src/mo Background process running periodically on the low priority work queue to calculate the CPU load and RAM usage and publish the `cpuload` topic. -У NuttX він також перевіряє використання стеку кожним процесом, і якщо воно падає нижче 300 байт, виводиться попередження, -яке також буде показано у файлі логу. +On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output, +which will also appear in the log file. - - -### Використання +### Usage {#load_mon_usage} ``` load_mon [arguments...] @@ -492,46 +463,47 @@ Source: [modules/logger](https://github.com/PX4/PX4-Autopilot/tree/main/src/modu ### Опис System logger which logs a configurable set of uORB topics and system printf messages -(`PX4_WARN` and `PX4_ERR`) to ULog files. Вони можуть бути використані для оцінки продуктивності системи та польоту, -налаштування, відтворення та аналізу збоїв. +(`PX4_WARN` and `PX4_ERR`) to ULog files. These can be used for system and flight performance evaluation, +tuning, replay and crash analysis. -Він підтримує 2 бекенди: +It supports 2 backends: -- Файли: запис файлів ULog до файлової системи (SD-карта) -- MAVLink: передача даних ULog через MAVLink клієнту (клієнт повинен це підтримувати) +- Files: write ULog files to the file system (SD card) +- MAVLink: stream ULog data via MAVLink to a client (the client must support this) -Обидва бекенди можуть бути активовані та використовуватися одночасно. +Both backends can be enabled and used at the same time. -Файловий бекенд підтримує 2 типи логів: повний (звичайний лог) і журнал місій. Журнал місії - це скорочений файл ulog, який можна використовувати, наприклад, для географічних міток або управління транспортним засобом. Його можна увімкнути та налаштувати за допомогою параметра SDLOG_MISSION. -Звичайний журнал завжди є підмножиною журналу місій. +The file backend supports 2 types of log files: full (the normal log) and a mission +log. The mission log is a reduced ulog file and can be used for example for geotagging or +vehicle management. It can be enabled and configured via SDLOG_MISSION parameter. +The normal log is always a superset of the mission log. ### Імплементація -Реалізація використовує два потоки: +The implementation uses two threads: - The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for data updates -- Потік запису, що записує дані у файл +- The writer thread, writing data to the file -Між ними знаходиться буфер запису з конфігурованим розміром (і ще один буфер фіксованого розміру для журналу місій). Він повинен бути великим, щоб уникнути втрати даних. +In between there is a write buffer with configurable size (and another fixed-size buffer for +the mission log). It should be large to avoid dropouts. ### Приклади -Типове використання для початку ведення журналу негайно: +Typical usage to start logging immediately: ``` logger start -e -t ``` -Або якщо вже працює: +Or if already running: ``` logger on ``` - - -### Використання +### Usage {#logger_usage} ``` logger [arguments...] @@ -572,11 +544,9 @@ Source: [modules/mag_bias_estimator](https://github.com/PX4/PX4-Autopilot/tree/m ### Опис -Онлайн-оцінювач похибки магнітометра. +Online magnetometer bias estimator. - - -### Використання +### Usage {#mag_bias_estimator_usage} ``` mag_bias_estimator [arguments...] @@ -594,11 +564,9 @@ Source: [modules/manual_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### Опис -Модуль споживає вхідні дані вручним керуванням, публікуючи одну установку керування вручну. +Module consuming manual_control_inputs publishing one manual_control_setpoint. - - -### Використання +### Usage {#manual_control_usage} ``` manual_control [arguments...] @@ -617,9 +585,9 @@ Source: [systemcmds/netman](https://github.com/PX4/PX4-Autopilot/tree/main/src/s ### Опис Network configuration manager saves the network settings in non-volatile -memory. On boot the `update` option will be run. Якщо конфігурація мережі -не існує. Значення за замовчуванням буде збережено в неплавучій пам'яті та -система перезавантажена. +memory. On boot the `update` option will be run. If a network configuration +does not exist. The default setting will be saved in non-volatile and the +system rebooted. #### update @@ -631,8 +599,8 @@ deletes the file and reboots the system. #### save The `save` option will save settings from non-volatile memory to a file named -`net.cfg` on the SD Card filesystem for editing. Використовуйте це, щоб відредагувати налаштування. -Збереження не негайно застосовує мережеві налаштування; користувач повинен перезавантажити стек польоту. +`net.cfg` on the SD Card filesystem for editing. Use this to edit the settings. +Save does not immediately apply the network settings; the user must reboot the flight stack. By contrast, the `update` command is run by the start-up script, commits the settings to non-volatile memory, and reboots the flight controller (which will then use the new settings). @@ -643,12 +611,10 @@ The `show` option will display the network settings in `net.cfg` to the console. ### Приклади $ netman save # Save the parameters to the SD card. -$ netman show # відображення поточних налаштувань. -$ netman update -i eth0 # зробити оновлення +$ netman show # display current settings. +$ netman update -i eth0 # do an update - - -### Використання +### Usage {#netman_usage} ``` netman [arguments...] @@ -669,11 +635,9 @@ Source: [drivers/pwm_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/d ### Опис -Вимірює вхід PWM на AUX5 (або MAIN5) через таймер захоплення ISR та публікує через повідомлення uORB 'pwm_input'. +Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input\` message. - - -### Використання +### Usage {#pwm_input_usage} ``` pwm_input [arguments...] @@ -697,11 +661,9 @@ and then publish as `rc_channels` and `manual_control_input`. ### Імплементація -Щоб зменшити затримку управління, модуль запланований на опублікування введення_управління. +To reduce control latency, the module is scheduled on input_rc publications. - - -### Використання +### Usage {#rc_update_usage} ``` rc_update [arguments...] @@ -719,7 +681,7 @@ Source: [modules/replay](https://github.com/PX4/PX4-Autopilot/tree/main/src/modu ### Опис -Цей модуль використовується для відтворення файлів ULog. +This module is used to replay ULog files. There are 2 environment variables used for configuration: `replay`, which must be set to an ULog file name - it's the log file to be replayed. The second is the mode, specified via `replay_mode`: @@ -729,16 +691,14 @@ the log file to be replayed. The second is the mode, specified via `replay_mode` - Generic otherwise: this can be used to replay any module(s), but the replay will be done with the same speed as the log was recorded. -Модуль зазвичай використовується разом з правилами видавця uORB, щоб вказати, які повідомлення потрібно відтворити. -Модуль відтворення просто опублікує всі повідомлення, які знаходяться в журналі. Це також застосовує параметри з -журналу. +The module is typically used together with uORB publisher rules, to specify which messages should be replayed. +The replay module will just publish all messages that are found in the log. It also applies the parameters from +the log. The replay procedure is documented on the [System-wide Replay](https://docs.px4.io/main/en/debug/system_wide_replay.html) page. - - -### Використання +### Usage {#replay_usage} ``` replay [arguments...] @@ -760,14 +720,12 @@ Source: [modules/events](https://github.com/PX4/PX4-Autopilot/tree/main/src/modu ### Опис -Фоновий процес, що періодично виконується в черзі завдань LP для виконання рутинних завдань. -Зараз він відповідає лише за сигнал тривоги на втрату RC. +Background process running periodically on the LP work queue to perform housekeeping tasks. +It is currently only responsible for tone alarm on RC Loss. -Завдання можна почати через CLI або теми uORB (vehicle_command з MAVLink тощо). +The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.). - - -### Використання +### Usage {#send_event_usage} ``` send_event [arguments...] @@ -787,9 +745,7 @@ Source: [modules/simulation/sensor_agp_sim](https://github.com/PX4/PX4-Autopilot Module to simulate auxiliary global position measurements with optional failure modes for SIH simulation. - - -### Використання +### Usage {#sensor_agp_sim_usage} ``` sensor_agp_sim [arguments...] @@ -807,9 +763,7 @@ Source: [modules/simulation/sensor_airspeed_sim](https://github.com/PX4/PX4-Auto ### Опис - - -### Використання +### Usage {#sensor_arispeed_sim_usage} ``` sensor_arispeed_sim [arguments...] @@ -827,9 +781,7 @@ Source: [modules/simulation/sensor_baro_sim](https://github.com/PX4/PX4-Autopilo ### Опис - - -### Використання +### Usage {#sensor_baro_sim_usage} ``` sensor_baro_sim [arguments...] @@ -847,9 +799,7 @@ Source: [modules/simulation/sensor_gps_sim](https://github.com/PX4/PX4-Autopilot ### Опис - - -### Використання +### Usage {#sensor_gps_sim_usage} ``` sensor_gps_sim [arguments...] @@ -867,9 +817,7 @@ Source: [modules/simulation/sensor_mag_sim](https://github.com/PX4/PX4-Autopilot ### Опис - - -### Використання +### Usage {#sensor_mag_sim_usage} ``` sensor_mag_sim [arguments...] @@ -887,26 +835,25 @@ Source: [modules/sensors](https://github.com/PX4/PX4-Autopilot/tree/main/src/mod ### Опис -Модуль сенсорів є центральним у всій системі. Він отримує вихід низького рівня від драйверів, перетворює його в більш придатну форму і публікує його для решти системи. +The sensors module is central to the whole system. It takes low-level output from drivers, turns +it into a more usable form, and publishes it for the rest of the system. -Надана функціональність включає в себе: +The provided functionality includes: - Read the output from the sensor drivers (`SensorGyro`, etc.). - Якщо існують кілька екземплярів того самого типу, виконуйте голосування та обробку аварійної ситуації. - Потім застосуйте обертання дошки та калібрування температури (якщо ввімкнено). And finally publish the data; one of the + If there are multiple of the same type, do voting and failover handling. + Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the topics is `SensorCombined`, used by many parts of the system. - Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or - on startup. Драйвери сенсора використовують інтерфейс ioctl для оновлення параметрів. For this to work properly, the + on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the sensor drivers must already be running when `sensors` is started. - Do sensor consistency checks and publish the `SensorsStatusImu` topic. ### Імплементація -Він запускається у власній темі і проводить опитування на поточну обрану тему гіроскопа. +It runs in its own thread and polls on the currently selected gyro topic. - - -### Використання +### Usage {#sensors_usage} ``` sensors [arguments...] @@ -925,9 +872,7 @@ Source: [modules/simulation/system_power_simulator](https://github.com/PX4/PX4-A ### Опис - - -### Використання +### Usage {#system_power_simulation_usage} ``` system_power_simulation [arguments...] @@ -945,11 +890,9 @@ Source: [drivers/tattu_can](https://github.com/PX4/PX4-Autopilot/tree/main/src/d ### Опис -Драйвер для зчитування даних з розумної батареї Tattu 12S 16000mAh. +Driver for reading data from the Tattu 12S 16000mAh smart battery. - - -### Використання +### Usage {#tattu_can_usage} ``` tattu_can [arguments...] @@ -967,14 +910,13 @@ Source: [modules/temperature_compensation](https://github.com/PX4/PX4-Autopilot/ ### Опис -Модуль компенсації температури дозволяє всім гіроскопам, акселерометрам та барометрам у системі бути температурно компенсованими. Модуль відстежує дані, які надходять від датчиків та оновлює пов'язану тему sensor_correction -кожного разу, коли виявляється зміна температури. Модуль також може бути налаштований для виконання обчислення коефіцієнта -наступного завантаження, що дозволяє обчислити калібрувальні коефіцієнти теплової калібрації під час -циклу температури автомобіля. +The temperature compensation module allows all of the gyro(s), accel(s), and baro(s) in the system to be temperature +compensated. The module monitors the data coming from the sensors and updates the associated sensor_correction topic +whenever a change in temperature is detected. The module can also be configured to perform the coeffecient calculation +routine at next boot, which allows the thermal calibration coeffecients to be calculated while the vehicle undergoes +a temperature cycle. - - -### Використання +### Usage {#temperature_compensation_usage} ``` temperature_compensation [arguments...] @@ -1004,9 +946,7 @@ Writes the RTC time cyclically to a file and reloads this value on startup. This allows monotonic time on systems that only have a software RTC (that is not battery powered). Explicitly setting the time backwards (e.g. via system_time) is still possible. - - -### Використання +### Usage {#time_persistor_usage} ``` time_persistor [arguments...] @@ -1026,23 +966,21 @@ Source: [systemcmds/tune_control](https://github.com/PX4/PX4-Autopilot/tree/main Command-line tool to control & test the (external) tunes. -Мелодії використовуються для надання слухових сповіщень та попереджень (наприклад, коли система озброєна, отримує позицію блокування тощо). -Інструмент вимагає, щоб був запущений драйвер, який може керувати темою управління tune_control uorb. +Tunes are used to provide audible notification and warnings (e.g. when the system arms, gets position lock, etc.). +The tool requires that a driver is running that can handle the tune_control uorb topic. -Інформацію про формат мелодії та попередньо визначені системні мелодії можна знайти тут: +Information about the tune format and predefined system tunes can be found here: https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/tunes/tune_definition.desc ### Приклади -Грайте системний мелодію #2: +Play system tune #2: ``` tune_control play -t 2 ``` - - -### Використання +### Usage {#tune_control_usage} ``` tune_control [arguments...] @@ -1069,7 +1007,7 @@ Source: [modules/uxrce_dds_client](https://github.com/PX4/PX4-Autopilot/tree/mai ### Опис -Клієнт UXRCE-DDS використовується для спілкування з агентом за допомогою тем uORB через послідовний або UDP. +UXRCE-DDS Client used to communicate uORB topics with an Agent over serial or UDP. ### Приклади @@ -1078,9 +1016,7 @@ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600 uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555 ``` - - -### Використання +### Usage {#uxrce_dds_client_usage} ``` uxrce_dds_client [arguments...] @@ -1109,11 +1045,9 @@ Source: [systemcmds/work_queue](https://github.com/PX4/PX4-Autopilot/tree/main/s ### Опис -Інструмент командного рядка для відображення статусу черги роботи. +Command-line tool to show work queue status. - - -### Використання +### Usage {#work_queue_usage} ``` work_queue [arguments...] diff --git a/docs/uk/modules/modules_template.md b/docs/uk/modules/modules_template.md index da38f46e12..a02a7276ee 100644 --- a/docs/uk/modules/modules_template.md +++ b/docs/uk/modules/modules_template.md @@ -16,15 +16,13 @@ Source: [templates/template_module](https://github.com/PX4/PX4-Autopilot/tree/ma ### Приклади -Приклад використання CLI: +CLI usage example: ``` module start -f -p 42 ``` - - -### Використання +### Usage {#module_usage} ``` module [arguments...] @@ -47,9 +45,7 @@ Source: [examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/ Приклад простого модуля, який виконується з черги завдань. - - -### Використання +### Usage {#work_item_example_usage} ``` work_item_example [arguments...] diff --git a/docs/uk/sim_sih/index.md b/docs/uk/sim_sih/index.md index bb3b9ceac7..c6e4f60611 100644 --- a/docs/uk/sim_sih/index.md +++ b/docs/uk/sim_sih/index.md @@ -58,6 +58,7 @@ To set up/start SIH: 2. Відкрийте QGroundControl і зачекайте, поки контролер польоту також завантажиться та підключиться. 3. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame: - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) + - SIH Hexacopter X currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently. - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) @@ -116,25 +117,31 @@ In this case you don't need the flight controller hardware. 1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md). 2. Виконайте відповідну команду make для кожного типу транспортного засобу (в корені репозиторію PX4-Autopilot): - - квадротор: + - Quadcopter ```sh make px4_sitl sihsim_quadx ``` - - Закріплені крила (літаки): + - Hexacopter + + ```sh + make px4_sitl sihsim_hex + ``` + + - Fixed-wing (plane) ```sh make px4_sitl sihsim_airplane ``` - - XVert VTOL tailsitter: + - XVert VTOL tailsitter ```sh make px4_sitl sihsim_xvert ``` - - Standard VTOL: + - Standard VTOL ```sh make px4_sitl sihsim_standard_vtol @@ -235,9 +242,10 @@ For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init. Динамічні моделі для різних транспортних засобів: -- Quadrotor: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). -- Fixed-wing: Inspired by the PhD thesis: "Dynamics modeling of agile fixed-wing unmanned aerial vehicles." Khan, Waqas, під керівництвом Nahon, Meyer, Університет Макгілла, докторська дисертація, 2016. -- Tailsitter: Inspired by the master's thesis: "Modeling and control of a flying wing tailsitter unmanned aerial vehicle." Chiappinelli, Romain, під керівництвом Nahon, Meyer, Університет Макгілла, магістерська робота, 2018. +- Quadcopter: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). +- Hexacopter: Equivalent to the Quadcopter but with a symmetric hexacopter x actuation setup. +- Fixed-wing: Inspired by the PhD thesis: "Dynamics modeling of agile fixed-wing unmanned aerial vehicles." Khan, Waqas, supervised by Nahon, Meyer, McGill University, PhD thesis, 2016. +- Tailsitter: Inspired by the master's thesis: "Modeling and control of a flying wing tailsitter unmanned aerial vehicle." Chiappinelli, Romain, supervised by Nahon, Meyer, McGill University, Masters thesis, 2018. ## Відео diff --git a/docs/uk/simulation/community_supported_simulators.md b/docs/uk/simulation/community_supported_simulators.md index 08509b5c96..8f6035c53a 100644 --- a/docs/uk/simulation/community_supported_simulators.md +++ b/docs/uk/simulation/community_supported_simulators.md @@ -12,10 +12,10 @@ These simulators are not maintained, tested, or supported, by the core developme Інструменти мають різний рівень підтримки своїми спільнотами (деякі добре підтримують, інші - ні). Питання про ці інструменти повинні порушуватися на [форумах для обговорення](../contribute/support.md#forums-and-chat) -| Симулятор | Опис | -| ----------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [FlightGear](../sim_flightgear/README.md) |

Симулятор який надає фізично та візуально реалістичні симуляції. Зокрема він може моделювати багато погодних умов, включаючи грози, сніг, дощ та град, а також може симулювати температурні режими та різні типи атмосферних течій. [Симуляція кількох засобів](../sim_flightgear/multi_vehicle.md) також підтримується.

Рухомі засоби, що підтримуються: Літак, Автожир, Ровер

| -| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| -| [JSBSim](../sim_jsbsim/README.md) |

Симулятор, який надає моделі просунутої динаміки польоту. Він може використовуватися для моделювання реалістичної динаміки польоту, заснованої на даних з аеродинамічної труби.

Рухомі засоби, що підтримуються: Літак, Квадрокоптер, Гексакоптер

| -| [AirSim](../sim_airsim/README.md) |

Міжплатформовий симулятор який надає фізично та візуально реалістичні симуляції. Цей симулятор ресурсомісткий та потребує значно потужніший комп'ютер ніж інші описані тут симулятори.

Рухомі засоби, що підтримуються: Iris (модель мультиротора та налаштування для PX4 квадрокоптера в конфігурації "X").

| -| [Simulation-In-Hardware](../sim_sih/README.md) (SIH) |

Альтернатива симуляції HITL, яка пропонує важку симуляцію в реальному часі безпосередньо на обладнанні автопілота. Цей симулятор реалізований на C++ у вигляді модуля PX4 безпосередньо в [коді](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulator_sih) прошивки.

Supported Vehicles: Plane, Quad, Tailsitter, Standard VTOL

| +| Симулятор | Опис | +| ----------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [Simulation-In-Hardware](../sim_sih/README.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL

| +| [FlightGear](../sim_flightgear/README.md) |

Симулятор який надає фізично та візуально реалістичні симуляції. Зокрема він може моделювати багато погодних умов, включаючи грози, сніг, дощ та град, а також може симулювати температурні режими та різні типи атмосферних течій. [Симуляція кількох засобів](../sim_flightgear/multi_vehicle.md) також підтримується.

Рухомі засоби, що підтримуються: Літак, Автожир, Ровер

| +| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| +| [JSBSim](../sim_jsbsim/README.md) |

Симулятор, який надає моделі просунутої динаміки польоту. Він може використовуватися для моделювання реалістичної динаміки польоту, заснованої на даних з аеродинамічної труби.

Рухомі засоби, що підтримуються: Літак, Квадрокоптер, Гексакоптер

| +| [AirSim](../sim_airsim/README.md) |

Міжплатформовий симулятор який надає фізично та візуально реалістичні симуляції. Цей симулятор ресурсомісткий та потребує значно потужніший комп'ютер ніж інші описані тут симулятори.

Рухомі засоби, що підтримуються: Iris (модель мультиротора та налаштування для PX4 квадрокоптера в конфігурації "X").

| From 44013e351cea501dd5ca115686d5af0708c15ce0 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Thu, 22 May 2025 08:12:42 +1000 Subject: [PATCH 025/130] New Crowdin translations - ko (#24893) Co-authored-by: Crowdin Bot --- docs/ko/SUMMARY.md | 1 + docs/ko/debug/failure_injection.md | 2 +- docs/ko/modules/modules_autotune.md | 8 +- docs/ko/modules/modules_command.md | 118 +++--- docs/ko/modules/modules_communication.md | 27 +- docs/ko/modules/modules_controller.md | 143 +++---- docs/ko/modules/modules_driver.md | 384 ++++-------------- .../modules/modules_driver_airspeed_sensor.md | 28 +- docs/ko/modules/modules_driver_baro.md | 60 +-- docs/ko/modules/modules_driver_camera.md | 4 +- .../modules/modules_driver_distance_sensor.md | 130 +++--- docs/ko/modules/modules_driver_imu.md | 150 ++----- docs/ko/modules/modules_driver_ins.md | 8 +- .../ko/modules/modules_driver_magnetometer.md | 56 +-- .../ko/modules/modules_driver_optical_flow.md | 8 +- .../modules/modules_driver_radio_control.md | 122 ++++++ docs/ko/modules/modules_driver_rpm_sensor.md | 4 +- docs/ko/modules/modules_driver_transponder.md | 4 +- docs/ko/modules/modules_estimator.md | 20 +- docs/ko/modules/modules_simulation.md | 4 +- docs/ko/modules/modules_system.md | 235 ++++------- docs/ko/modules/modules_template.md | 10 +- docs/ko/sim_sih/index.md | 18 +- .../community_supported_simulators.md | 14 +- 24 files changed, 568 insertions(+), 990 deletions(-) create mode 100644 docs/ko/modules/modules_driver_radio_control.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index 66b6ad276a..ac7dc4f91c 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -739,6 +739,7 @@ - [자기 센서](modules/modules_driver_magnetometer.md) - [광류 센서](modules/modules_driver_optical_flow.md) - [Rpm Sensor](modules/modules_driver_rpm_sensor.md) + - [Radio Control](modules/modules_driver_radio_control.md) - [Transponder](modules/modules_driver_transponder.md) - [추정기](modules/modules_estimator.md) - [시뮬레이션](modules/modules_simulation.md) diff --git a/docs/ko/debug/failure_injection.md b/docs/ko/debug/failure_injection.md index a73ee69017..9c33504065 100644 --- a/docs/ko/debug/failure_injection.md +++ b/docs/ko/debug/failure_injection.md @@ -61,7 +61,7 @@ failure [-i ] - _instance number_ (optional): Instance number of affected sensor. 0 (기본값) 지정된 유형의 모든 센서를 나타냅니다. -### 예 +### Example To simulate losing RC signal without having to turn off your RC controller: diff --git a/docs/ko/modules/modules_autotune.md b/docs/ko/modules/modules_autotune.md index dc963cf6d3..ce100baefd 100644 --- a/docs/ko/modules/modules_autotune.md +++ b/docs/ko/modules/modules_autotune.md @@ -6,9 +6,7 @@ Source: [modules/fw_autotune_attitude_control](https://github.com/PX4/PX4-Autopi ### 설명 - - -### 사용법 +### Usage {#fw_autotune_attitude_control_usage} ``` fw_autotune_attitude_control [arguments...] @@ -27,9 +25,7 @@ Source: [modules/mc_autotune_attitude_control](https://github.com/PX4/PX4-Autopi ### 설명 - - -### 사용법 +### Usage {#mc_autotune_attitude_control_usage} ``` mc_autotune_attitude_control [arguments...] diff --git a/docs/ko/modules/modules_command.md b/docs/ko/modules/modules_command.md index 4ebd49cd2b..6fba14c9ac 100644 --- a/docs/ko/modules/modules_command.md +++ b/docs/ko/modules/modules_command.md @@ -8,9 +8,7 @@ Source: [systemcmds/actuator_test](https://github.com/PX4/PX4-Autopilot/tree/mai WARNING: remove all props before using this command. - - -### 사용법 +### Usage {#actuator_test_usage} ``` actuator_test [arguments...] @@ -30,13 +28,13 @@ actuator_test [arguments...] iterate-servos Iterate all servos deflecting one after the other ``` -## dumpfile +## bl_update Source: [systemcmds/bl_update](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bl_update) -Utility to flash the bootloader from a file +Utility to flash the bootloader from a file -### 사용법 +### Usage {#bl_update_usage} ``` bl_update [arguments...] @@ -50,45 +48,43 @@ bl_update [arguments...] Source: [systemcmds/bsondump](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bsondump) -Utility to read BSON from a file and print or output document size. +Utility to read BSON from a file and print or output document size. -### 사용법 +### Usage {#bsondump_usage} ``` bsondump [arguments...] The BSON file to decode and print. ``` -## dyn +## dumpfile Source: [systemcmds/dumpfile](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dumpfile) -Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. +Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. -### 사용법 +### Usage {#dumpfile_usage} ``` dumpfile [arguments...] File to dump ``` -## esc_calib +## dyn Source: [systemcmds/dyn](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dyn) ### 설명 -소스: systemcmds/failure +Load and run a dynamic PX4 module, which was not compiled into the PX4 binary. -### 예 +### Example ``` dyn ./hello.px4mod start ``` - - -### 사용법 +### Usage {#dyn_usage} ``` dyn [arguments...] @@ -114,9 +110,7 @@ Test the GPS failsafe by stopping GPS: failure gps off - - -### 사용법 +### Usage {#failure_usage} ``` failure [arguments...] @@ -164,9 +158,7 @@ Set the output value on device /dev/gpio1 to high gpio write /dev/gpio1 1 ``` - - -### 사용법 +### Usage {#gpio_usage} ``` gpio [arguments...] @@ -190,9 +182,7 @@ Hardfault utility Used in startup scripts to handle hardfaults - - -### 사용법 +### Usage {#hardfault_log_usage} ``` hardfault_log [arguments...] @@ -219,9 +209,9 @@ hardfault_log [arguments...] Source: [systemcmds/hist](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hist) -Command-line tool to show the px4 message history. There are no arguments. +Command-line tool to show the px4 message history. There are no arguments. -### 사용법 +### Usage {#hist_usage} ``` hist [arguments...] @@ -231,9 +221,9 @@ hist [arguments...] Source: [systemcmds/i2cdetect](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/i2cdetect) -Utility to scan for I2C devices on a particular bus. +Utility to scan for I2C devices on a particular bus. -### 사용법 +### Usage {#i2cdetect_usage} ``` i2cdetect [arguments...] @@ -263,9 +253,7 @@ Blink the first LED 5 times in blue: led_control blink -c blue -l 0 -n 5 ``` - - -### 사용법 +### Usage {#led_control_usage} ``` led_control [arguments...] @@ -305,9 +293,7 @@ Utility to listen on uORB topics and print the data to the console. The listener can be exited any time by pressing Ctrl+C, Esc, or Q. - - -### 사용법 +### Usage {#listener_usage} ``` listener [arguments...] @@ -325,9 +311,9 @@ listener [arguments...] Source: [systemcmds/mft](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft) -Utility interact with the manifest +Utility interact with the manifest -### 사용법 +### Usage {#mfd_usage} ``` mfd [arguments...] @@ -339,9 +325,9 @@ mfd [arguments...] Source: [systemcmds/mft_cfg](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft_cfg) -Tool to set and get manifest configuration +Tool to set and get manifest configuration -### 사용법 +### Usage {#mft_cfg_usage} ``` mft_cfg [arguments...] @@ -360,9 +346,9 @@ mft_cfg [arguments...] Source: [systemcmds/mtd](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mtd) -Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) +Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) -### 사용법 +### Usage {#mtd_usage} ``` mtd [arguments...] @@ -393,9 +379,7 @@ Start an NSH shell on a given port. This was previously used to start a shell on the USB serial port. Now there runs mavlink, and it is possible to use a shell over mavlink. - - -### 사용법 +### Usage {#nshterm_usage} ``` nshterm [arguments...] @@ -433,9 +417,7 @@ param set SYS_AUTOCONFIG 1 reboot ``` - - -### 사용법 +### Usage {#param_usage} ``` param [arguments...] @@ -513,9 +495,7 @@ Source: [modules/payload_deliverer](https://github.com/PX4/PX4-Autopilot/tree/ma Handles payload delivery with either Gripper or a Winch with an appropriate timeout / feedback sensor setting, and communicates back the delivery result as an acknowledgement internally - - -### 사용법 +### Usage {#payload_deliverer_usage} ``` payload_deliverer [arguments...] @@ -537,9 +517,9 @@ payload_deliverer [arguments...] Source: [systemcmds/perf](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/perf) -Tool to print performance counters +Tool to print performance counters -### 사용법 +### Usage {#perf_usage} ``` perf [arguments...] @@ -554,9 +534,9 @@ perf [arguments...] Source: [systemcmds/reboot](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/reboot) -Reboot the system +Reboot the system -### 사용법 +### Usage {#reboot_usage} ``` reboot [arguments...] @@ -569,9 +549,9 @@ reboot [arguments...] Source: [systemcmds/sd_bench](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_bench) -Test the speed of an SD Card +Test the speed of an SD Card -### 사용법 +### Usage {#sd_bench_usage} ``` sd_bench [arguments...] @@ -592,9 +572,9 @@ sd_bench [arguments...] Source: [systemcmds/sd_stress](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_stress) -Test operations on an SD Card +Test operations on an SD Card -### 사용법 +### Usage {#sd_stress_usage} ``` sd_stress [arguments...] @@ -612,9 +592,7 @@ Pass data from one device to another. This can be used to use u-center connected to USB with a GPS on a serial port. - - -### 사용법 +### Usage {#serial_passthru_usage} ``` serial_passthru [arguments...] @@ -644,9 +622,7 @@ system_time set 1600775044 system_time get ``` - - -### 사용법 +### Usage {#system_time_usage} ``` system_time [arguments...] @@ -660,9 +636,9 @@ system_time [arguments...] Source: [systemcmds/top](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/top) -Monitor running processes and their CPU, stack usage, priority and state +Monitor running processes and their CPU, stack usage, priority and state -### 사용법 +### Usage {#top_usage} ``` top [arguments...] @@ -674,9 +650,9 @@ top [arguments...] Source: [systemcmds/usb_connected](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/usb_connected) Utility to check if USB is connected. Was previously used in startup scripts. -A return value of 0 means USB is connected, 1 otherwise. +A return value of 0 means USB is connected, 1 otherwise. -### 사용법 +### Usage {#usb_connected_usage} ``` usb_connected [arguments...] @@ -686,9 +662,9 @@ usb_connected [arguments...] Source: [systemcmds/ver](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/ver) -Tool to print various version information +Tool to print various version information -### 사용법 +### Usage {#ver_usage} ``` ver [arguments...] diff --git a/docs/ko/modules/modules_communication.md b/docs/ko/modules/modules_communication.md index dc95690bf9..44d6ba4615 100644 --- a/docs/ko/modules/modules_communication.md +++ b/docs/ko/modules/modules_communication.md @@ -4,9 +4,9 @@ Source: [drivers/telemetry/frsky_telemetry](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/frsky_telemetry) -FrSky 텔레메트리를 지원합니다. D 또는 S.PORT 프로토콜을 자동으로 감지합니다. +FrSky 텔레메트리를 지원합니다. D 또는 S.PORT 프로토콜을 자동으로 감지합니다. -### 사용법 +### Usage {#frsky_telemetry_usage} ``` frsky_telemetry [arguments...] @@ -64,9 +64,7 @@ mavlink start -u 14556 -r 1000000 mavlink stream -u 14556 -s HIGHRES_IMU -r 50 ``` - - -### 사용법 +### Usage {#mavlink_usage} ``` mavlink [arguments...] @@ -129,30 +127,29 @@ Source: [systemcmds/uorb](https://github.com/PX4/PX4-Autopilot/tree/main/src/sys ### 설명 -uORB는 모듈 간의 통신에 사용되는 내부 pub-sub 메시징 시스템입니다. +uORB is the internal pub-sub messaging system, used for communication between modules. ### 구현 -구현은 비동기식이며 잠금이 없습니다. 게시자는 구독자를 기다리지 않으며, 그 반대도 마찬가지입니다. -이것은 발행자와 구독자 사이에 별도의 버퍼를 가짐으로써 달성됩니다. +The implementation is asynchronous and lock-free, ie. a publisher does not wait for a subscriber and vice versa. +This is achieved by having a separate buffer between a publisher and a subscriber. -코드는 메모리 공간과 메시지 교환 대기 시간을 최소화하도록 최적화되었습니다. +The code is optimized to minimize the memory footprint and the latency to exchange messages. -Messages are defined in the `/msg` directory. 빌드 타임에 C/C++ 코드로 변환됩니다. +Messages are defined in the `/msg` directory. They are converted into C/C++ code at build-time. -ORB_USE_PUBLISHER_RULES로 컴파일하면, uORB 게시 규칙이 있는 파일을 사용하여, 어떤 모듈이 어떤 주제를 게시할 수 있는 지 설정할 수 있습니다. 이것은 시스템 전체 재생에 사용됩니다. +If compiled with ORB_USE_PUBLISHER_RULES, a file with uORB publication rules can be used to configure which +modules are allowed to publish which topics. This is used for system-wide replay. ### 예 -주제 게시 비율을 모니터링합니다. Besides `top`, this is an important command for general system inspection: +Monitor topic publication rates. Besides `top`, this is an important command for general system inspection: ``` uorb top ``` - - -### 사용법 +### Usage {#uorb_usage} ``` uorb [arguments...] diff --git a/docs/ko/modules/modules_controller.md b/docs/ko/modules/modules_controller.md index edc767dbe7..c759734d7b 100644 --- a/docs/ko/modules/modules_controller.md +++ b/docs/ko/modules/modules_controller.md @@ -16,9 +16,7 @@ Currently it is feeding the `manual_control_setpoint` topic directly to the actu 제어 대기 시간을 줄이기 위하여, 모듈은 IMU 드라이버에서 게시한 자이로 주제를 직접 폴링합니다. - - -### 사용법 +### Usage {#airship_att_control_usage} ``` airship_att_control [arguments...] @@ -36,11 +34,10 @@ Source: [modules/control_allocator](https://github.com/PX4/PX4-Autopilot/tree/ma ### 설명 -이것은 제어 할당을 구현합니다. 토크 및 추력 설정값을 입력으로 사용하고, 액추에이터 설정값 메시지를 출력합니다. +This implements control allocation. It takes torque and thrust setpoints +as inputs and outputs actuator setpoint messages. - - -### 사용법 +### Usage {#control_allocator_usage} ``` control_allocator [arguments...] @@ -58,11 +55,10 @@ Source: [modules/flight_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/ ### 설명 -이것은 모든 모드에 대한 설정값 생성을 구현합니다. 차량의 현재 모드 상태를 컨트롤러에 대한 입력 및 출력 설정값으로 사용합니다. +This implements the setpoint generation for all modes. It takes the current mode state of the vehicle as input +and outputs setpoints for controllers. - - -### 사용법 +### Usage {#flight_mode_manager_usage} ``` flight_mode_manager [arguments...] @@ -80,11 +76,9 @@ Source: [modules/fw_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### 설명 -fw_att_control은 고정익 자세 컨트롤러입니다. +fw_att_control is the fixed wing attitude controller. - - -### 사용법 +### Usage {#fw_att_control_usage} ``` fw_att_control [arguments...] @@ -105,9 +99,7 @@ Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/ fw_pos_control is the fixed-wing position controller. - - -### 사용법 +### Usage {#fw_pos_control_usage} ``` fw_pos_control [arguments...] @@ -128,9 +120,7 @@ Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main fw_rate_control is the fixed-wing rate controller. - - -### 사용법 +### Usage {#fw_rate_control_usage} ``` fw_rate_control [arguments...] @@ -149,21 +139,19 @@ Source: [modules/mc_att_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### 설명 -이것은 멀티콥터 자세 컨트롤러를 구현합니다. It takes attitude +This implements the multicopter attitude controller. It takes attitude setpoints (`vehicle_attitude_setpoint`) as inputs and outputs a rate setpoint. -컨트롤러에는 각도 오류에 대한 P 루프가 있습니다. +The controller has a P loop for angular error -간행물: 구현된 쿼터니언 태도 제어를 문서화, -제목: 비선형 쿼드로콥터 자세 제어(2013), -저자: Dario Brescianini, Markus Hehn and Raffaello D'Andrea -동적 시스템 및 제어 연구소(IDSC), ETH 취리히 +Publication documenting the implemented Quaternion Attitude Control: +Nonlinear Quadrocopter Attitude Control (2013) +by Dario Brescianini, Markus Hehn and Raffaello D'Andrea +Institute for Dynamic Systems and Control (IDSC), ETH Zurich https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf - - -### 사용법 +### Usage {#mc_att_control_usage} ``` mc_att_control [arguments...] @@ -182,14 +170,14 @@ Source: [modules/mc_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/ ### 설명 -컨트롤러에는 위치 오류용 P 루프와 속도 오류용 PID 루프의 두 가지 루프가 있습니다. -속도 컨트롤러의 출력은 추력 방향(즉, 멀티콥터 방향에 대한 회전 행렬)과 추력 스칼라(즉, 멀티콥터 추력 자체)로 분할되는 추력 벡터입니다. +The controller has two loops: a P loop for position error and a PID loop for velocity error. +Output of the velocity controller is thrust vector that is split to thrust direction +(i.e. rotation matrix for multicopter orientation) and thrust scalar (i.e. multicopter thrust itself). -컨트롤러는 작업에 오일러 각도를 사용하지 않으며, 보다 인간 친화적인 제어 및 로깅을 위해서만 생성됩니다. +The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and +logging. - - -### 사용법 +### Usage {#mc_pos_control_usage} ``` mc_pos_control [arguments...] @@ -208,14 +196,12 @@ Source: [modules/mc_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main ### 설명 -이것은 멀티콥터 속도 컨트롤러를 구현합니다. It takes rate setpoints (in acro mode +This implements the multicopter rate controller. It takes rate setpoints (in acro mode via `manual_control_setpoint` topic) as inputs and outputs actuator control messages. -컨트롤러에는 각속도 오류에 대한 PID 루프가 있습니다. +The controller has a PID loop for angular rate error. - - -### 사용법 +### Usage {#mc_rate_control_usage} ``` mc_rate_control [arguments...] @@ -234,8 +220,9 @@ Source: [modules/navigator](https://github.com/PX4/PX4-Autopilot/tree/main/src/m ### 설명 -자율 비행 모드를 담당하는 모듈입니다. 여기에는 임무(데이터맨에서 읽기), 이륙 및 RTL이 포함됩니다. -또한, 지오펜스 위반 검사를 담당합니다. +Module that is responsible for autonomous flight modes. This includes missions (read from dataman), +takeoff and RTL. +It is also responsible for geofence violation checking. ### 구현 @@ -245,9 +232,7 @@ The member `_navigation_mode` contains the current active mode. Navigator publishes position setpoint triplets (`position_setpoint_triplet_s`), which are then used by the position controller. - - -### 사용법 +### Usage {#navigator_usage} ``` navigator [arguments...] @@ -271,9 +256,7 @@ Source: [modules/rover_ackermann](https://github.com/PX4/PX4-Autopilot/tree/main Rover ackermann module. - - -### 사용법 +### Usage {#rover_ackermann_usage} ``` rover_ackermann [arguments...] @@ -293,9 +276,7 @@ Source: [modules/rover_differential](https://github.com/PX4/PX4-Autopilot/tree/m Rover differential module. - - -### 사용법 +### Usage {#rover_differential_usage} ``` rover_differential [arguments...] @@ -315,9 +296,7 @@ Source: [modules/rover_mecanum](https://github.com/PX4/PX4-Autopilot/tree/main/s Rover mecanum module. - - -### 사용법 +### Usage {#rover_mecanum_usage} ``` rover_mecanum [arguments...] @@ -335,21 +314,21 @@ Source: [modules/rover_pos_control](https://github.com/PX4/PX4-Autopilot/tree/ma ### 설명 -L1 컨트롤러를 사용하여 그라운드 로버의 위치를 제어합니다. +Controls the position of a ground rover using an L1 controller. Publishes `vehicle_thrust_setpoint (only in x) and vehicle_torque_setpoint (only yaw)` messages at IMU_GYRO_RATEMAX. ### 구현 -현재 이 구현은 일부 모드만 지원합니다. +Currently, this implementation supports only a few modes: -- 완전 수동: 스로틀 및 편요각 제어가 액츄에이터에 직접 전달됩니다. -- 자동 미션: 로버가 미션을 실행합니다. -- 배회: 로버가 배회 반경 내로 이동한 다음 모터를 중지합니다. +- Full manual: Throttle and yaw controls are passed directly through to the actuators +- Auto mission: The rover runs missions +- Loiter: The rover will navigate to within the loiter radius, then stop the motors ### 예 -CLI 사용 예: +CLI usage example: ``` rover_pos_control start @@ -357,9 +336,7 @@ rover_pos_control status rover_pos_control stop ``` - - -### 사용법 +### Usage {#rover_pos_control_usage} ``` rover_pos_control [arguments...] @@ -382,9 +359,7 @@ It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages. ``` - - -### 사용법 +### Usage {#spacecraft_usage} ``` spacecraft [arguments...] @@ -402,20 +377,20 @@ Source: [modules/uuv_att_control](https://github.com/PX4/PX4-Autopilot/tree/main ### 설명 -무인수중선(UUV)의 자세를 제어합니다. +Controls the attitude of an unmanned underwater vehicle (UUV). Publishes `vehicle_thrust_setpont` and `vehicle_torque_setpoint` messages at a constant 250Hz. ### 구현 -현재 이 구현은 일부 모드만 지원합니다. +Currently, this implementation supports only a few modes: -- 완전 수동: 롤, 피치, 요 및 스로틀 컨트롤이 액추에이터에 직접 전달됩니다. -- 자동 임무: 무인수중선이 임무를 실행합니다. +- Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators +- Auto mission: The uuv runs missions ### 예 -CLI 사용 예: +CLI usage example: ``` uuv_att_control start @@ -423,9 +398,7 @@ uuv_att_control status uuv_att_control stop ``` - - -### 사용법 +### Usage {#uuv_att_control_usage} ``` uuv_att_control [arguments...] @@ -443,19 +416,19 @@ Source: [modules/uuv_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main ### 설명 -무인수중선(UUV)의 자세를 제어합니다. +Controls the attitude of an unmanned underwater vehicle (UUV). Publishes `attitude_setpoint` messages. ### 구현 -현재 이 구현은 일부 모드만 지원합니다. +Currently, this implementation supports only a few modes: -- 완전 수동: 롤, 피치, 요 및 스로틀 컨트롤이 액추에이터에 직접 전달됩니다. -- 자동 임무: 무인수중선이 임무를 실행합니다. +- Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators +- Auto mission: The uuv runs missions ### 예 -CLI 사용 예: +CLI usage example: ``` uuv_pos_control start @@ -463,9 +436,7 @@ uuv_pos_control status uuv_pos_control stop ``` - - -### 사용법 +### Usage {#uuv_pos_control_usage} ``` uuv_pos_control [arguments...] @@ -483,11 +454,9 @@ Source: [modules/vtol_att_control](https://github.com/PX4/PX4-Autopilot/tree/mai ### 설명 -fw_att_control은 고정익 자세 컨트롤러입니다. +fw_att_control is the fixed wing attitude controller. - - -### 사용법 +### Usage {#vtol_att_control_usage} ``` vtol_att_control [arguments...] diff --git a/docs/ko/modules/modules_driver.md b/docs/ko/modules/modules_driver.md index 3fc256ad2a..a0209ba330 100644 --- a/docs/ko/modules/modules_driver.md +++ b/docs/ko/modules/modules_driver.md @@ -3,23 +3,22 @@ 하위 카테고리: - [Airspeed Sensor](modules_driver_airspeed_sensor.md) -- [Transponder](modules_driver_transponder.md) -- [Imu](modules_driver_imu.md) -- [Rpm Sensor](modules_driver_rpm_sensor.md) -- [Magnetometer](modules_driver_magnetometer.md) +- [Baro](modules_driver_baro.md) - [Camera](modules_driver_camera.md) - [Distance Sensor](modules_driver_distance_sensor.md) -- [Optical Flow](modules_driver_optical_flow.md) +- [Imu](modules_driver_imu.md) - [Ins](modules_driver_ins.md) -- [Baro](modules_driver_baro.md) +- [Magnetometer](modules_driver_magnetometer.md) +- [Optical Flow](modules_driver_optical_flow.md) +- [Radio Control](modules_driver_radio_control.md) +- [Rpm Sensor](modules_driver_rpm_sensor.md) +- [Transponder](modules_driver_transponder.md) ## MCP23009 Source: [drivers/gpio/mcp23009](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gpio/mcp23009) - - -### 사용법 +### Usage {#MCP23009_usage} ``` MCP23009 [arguments...] @@ -53,11 +52,9 @@ Source: [drivers/adc/board_adc](https://github.com/PX4/PX4-Autopilot/tree/main/s ### 설명 -ADC 드라이버 +ADC driver. - - -### 사용법 +### Usage {#adc_usage} ``` adc [arguments...] @@ -89,9 +86,7 @@ It is enabled/disabled using the parameter, and is disabled by default. If enabled, internal ADCs are not used. - - -### 사용법 +### Usage {#ads1115_usage} ``` ads1115 [arguments...] @@ -117,13 +112,11 @@ Source: [drivers/osd/atxxxx](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### 설명 -예를 들어 OmnibusF4SD 보드에 장착된 ATXXXX 칩용 OSD 드라이버. +OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example. -OSD_ATXXXX_CFG 매개변수로 활성화합니다. +It can be enabled with the OSD_ATXXXX_CFG parameter. - - -### 사용법 +### Usage {#atxxxx_usage} ``` atxxxx [arguments...] @@ -149,19 +142,18 @@ Source: [drivers/smart_battery/batmon](https://github.com/PX4/PX4-Autopilot/tree ### 설명 -BatMon 지원 스마트 배터리와 SMBUS 통신용 드라이버 설정/사용 정보: https://rotoye.com/batmon-tutorial/ +Driver for SMBUS Communication with BatMon enabled smart-battery +Setup/usage information: https://rotoye.com/batmon-tutorial/ ### 예 -주소 0x0B에서 시작하려면 버스 4에서 +To start at address 0x0B, on bus 4 ``` batmon start -X -a 11 -b 4 ``` - - -### 사용법 +### Usage {#batmon_usage} ``` batmon [arguments...] @@ -193,19 +185,17 @@ Source: [drivers/batt_smbus](https://github.com/PX4/PX4-Autopilot/tree/main/src/ ### 설명 -BQ40Z50 연료 게이지 IC용 스마트 배터리 드라이버. +Smart battery driver for the BQ40Z50 fuel gauge IC. ### 예 -매개변수를 설정하기 위해 플래시에 쓰기. address, number_of_bytes, byte0, ... , byteN +To write to flash to set parameters. address, number_of_bytes, byte0, ... , byteN ``` batt_smbus -X write_flash 19069 2 27 0 ``` - - -### 사용법 +### Usage {#batt_smbus_usage} ``` batt_smbus [arguments...] @@ -246,9 +236,7 @@ batt_smbus [arguments...] Source: [drivers/telemetry/bst](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/telemetry/bst) - - -### 사용법 +### Usage {#bst_usage} ``` bst [arguments...] @@ -268,46 +256,23 @@ bst [arguments...] status print status info ``` -## crsf_rc - -Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) - -### 설명 - -This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data - - - -### 사용법 - -``` -crsf_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## dshot Source: [drivers/dshot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/dshot) ### 설명 -이것은 DShot 출력 드라이버입니다. fmu 드라이버와 유사하며, PWM 대신 ESC 통신 프로토콜로 DShot을 사용하기 위하여 사용할 수 있습니다. +This is the DShot output driver. It is similar to the fmu driver, and can be used as drop-in replacement +to use DShot as ESC communication protocol instead of PWM. On startup, the module tries to occupy all available pins for DShot output. It skips all pins already in use (e.g. by a camera trigger module). -모터 1 영구 역회전 : +It supports: - DShot150, DShot300, DShot600 -- 별도의 UART를 통한 텔레메트리와 esc_status 메시지로 게시 -- CLI를 통해 DShot 명령 보내기 +- telemetry via separate UART and publishing as esc_status message +- sending DShot commands via CLI ### 예 @@ -320,9 +285,7 @@ dshot save -m 1 After saving, the reversed direction will be regarded as the normal one. So to reverse again repeat the same commands. - - -### 사용법 +### Usage {#dshot_usage} ``` dshot [arguments...] @@ -370,41 +333,13 @@ dshot [arguments...] status print status info ``` -## dsm_rc - -Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) - -### 설명 - -This module does Spektrum DSM RC input parsing. - - - -### 사용법 - -``` -dsm_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` - ## fake_gps Source: [examples/fake_gps](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/fake_gps) ### 설명 - - -### 사용법 +### Usage {#fake_gps_usage} ``` fake_gps [arguments...] @@ -422,9 +357,7 @@ Source: [examples/fake_imu](https://github.com/PX4/PX4-Autopilot/tree/main/src/e ### 설명 - - -### 사용법 +### Usage {#fake_imu_usage} ``` fake_imu [arguments...] @@ -445,9 +378,7 @@ Source: [examples/fake_magnetometer](https://github.com/PX4/PX4-Autopilot/tree/m Publish the earth magnetic field as a fake magnetometer (sensor_mag). Requires vehicle_attitude and vehicle_gps_position. - - -### 사용법 +### Usage {#fake_magnetometer_usage} ``` fake_magnetometer [arguments...] @@ -472,21 +403,19 @@ Most boards are configured to enable/start the driver on a specified UART using ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` ft_technologies_serial start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` ft_technologies_serial stop ``` - - -### 사용법 +### Usage {#ft_technologies_serial_usage} ``` ft_technologies_serial [arguments...] @@ -497,30 +426,6 @@ ft_technologies_serial [arguments...] stop Stop driver ``` -## ghst_rc - -Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) - -### 설명 - -This module does Ghost (GHST) RC input parsing. - - - -### 사용법 - -``` -ghst_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## gimbal Source: [modules/gimbal](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/gimbal) @@ -540,9 +445,7 @@ Test the output by setting a angles (all omitted axes are set to 0): gimbal test pitch -45 yaw 30 ``` - - -### 사용법 +### Usage {#gimbal_usage} ``` gimbal [arguments...] @@ -597,9 +500,7 @@ Initiate warm restart of GPS device gps reset warm ``` - - -### 사용법 +### Usage {#gps_usage} ``` gps [arguments...] @@ -634,9 +535,7 @@ Source: [modules/simulation/gz_bridge](https://github.com/PX4/PX4-Autopilot/tree ### 설명 - - -### 사용법 +### Usage {#gz_bridge_usage} ``` gz_bridge [arguments...] @@ -667,9 +566,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 사용법 +### Usage {#ina220_usage} ``` ina220 [arguments...] @@ -711,9 +608,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 사용법 +### Usage {#ina226_usage} ``` ina226 [arguments...] @@ -753,9 +648,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 사용법 +### Usage {#ina228_usage} ``` ina228 [arguments...] @@ -795,9 +688,7 @@ the -f flag. If this flag is set, then if initialization fails, the driver will every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver. - - -### 사용법 +### Usage {#ina238_usage} ``` ina238 [arguments...] @@ -830,9 +721,7 @@ IridiumSBD driver. Creates a virtual serial port that another module can use for communication (e.g. mavlink). - - -### 사용법 +### Usage {#iridiumsbd_usage} ``` iridiumsbd [arguments...] @@ -854,9 +743,7 @@ iridiumsbd [arguments...] Source: [drivers/irlock](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/irlock) - - -### 사용법 +### Usage {#irlock_usage} ``` irlock [arguments...] @@ -884,9 +771,7 @@ Source: [drivers/linux_pwm_out](https://github.com/PX4/PX4-Autopilot/tree/main/s Linux PWM output driver with board-specific backend implementation. - - -### 사용법 +### Usage {#linux_pwm_out_usage} ``` linux_pwm_out [arguments...] @@ -902,9 +787,7 @@ linux_pwm_out [arguments...] Source: [drivers/magnetometer/lsm303agr](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm303agr) - - -### 사용법 +### Usage {#lsm303agr_usage} ``` lsm303agr [arguments...] @@ -940,15 +823,13 @@ Converts uORB messages to MSP telemetry packets ### 예 -CLI 사용 예: +CLI usage example: ``` msp_osd ``` - - -### 사용법 +### Usage {#msp_osd_usage} ``` msp_osd [arguments...] @@ -976,9 +857,7 @@ neopixel -n 8 To drive all available leds. - - -### 사용법 +### Usage {#newpixel_usage} ``` newpixel [arguments...] @@ -992,9 +871,7 @@ newpixel [arguments...] Source: [drivers/optical_flow/paa3905](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paa3905) - - -### 사용법 +### Usage {#paa3905_usage} ``` paa3905 [arguments...] @@ -1020,9 +897,7 @@ paa3905 [arguments...] Source: [drivers/optical_flow/paw3902](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/paw3902) - - -### 사용법 +### Usage {#paw3902_usage} ``` paw3902 [arguments...] @@ -1066,9 +941,7 @@ It is typically started with: pca9685_pwm_out start -a 0x40 -b 1 ``` - - -### 사용법 +### Usage {#pca9685_pwm_out_usage} ``` pca9685_pwm_out [arguments...] @@ -1092,9 +965,7 @@ Source: [drivers/power_monitor/pm_selector_auterion](https://github.com/PX4/PX4- Driver for starting and auto-detecting different power monitors. - - -### 사용법 +### Usage {#pm_selector_auterion_usage} ``` pm_selector_auterion [arguments...] @@ -1110,9 +981,7 @@ pm_selector_auterion [arguments...] Source: [drivers/optical_flow/pmw3901](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/pmw3901) - - -### 사용법 +### Usage {#pmw3901_usage} ``` pmw3901 [arguments...] @@ -1142,9 +1011,7 @@ Source: [drivers/pps_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src This implements capturing PPS information from the GNSS module and calculates the drift between PPS and Real-time clock. - - -### 사용법 +### Usage {#pps_capture_usage} ``` pps_capture [arguments...] @@ -1166,9 +1033,7 @@ This module is responsible for driving the output pins. For boards without a sep (eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the px4io driver is used for main ones. - - -### 사용법 +### Usage {#pwm_out_usage} ``` pwm_out [arguments...] @@ -1194,9 +1059,7 @@ mix them with any loaded mixer and output the result to the It is used in SITL and HITL. - - -### 사용법 +### Usage {#pwm_out_sim_usage} ``` pwm_out_sim [arguments...] @@ -1214,9 +1077,7 @@ pwm_out_sim [arguments...] Source: [drivers/optical_flow/px4flow](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/px4flow) - - -### 사용법 +### Usage {#px4flow_usage} ``` px4flow [arguments...] @@ -1244,9 +1105,7 @@ Source: [drivers/px4io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drive Output driver communicating with the IO co-processor. - - -### 사용법 +### Usage {#px4io_usage} ``` px4io [arguments...] @@ -1280,46 +1139,11 @@ px4io [arguments...] status print status info ``` -## rc_input - -Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) - -### 설명 - -This module does the RC input parsing and auto-selecting the method. Supported methods are: - -- PPM -- SBUS -- DSM -- SUMD -- ST24 -- TBS Crossfire (CRSF) - - - -### 사용법 - -``` -rc_input [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - bind Send a DSM bind command (module must be running) - - stop - - status print status info -``` - ## rgbled Source: [drivers/lights/rgbled_ncp5623c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_ncp5623c) - - -### 사용법 +### Usage {#rgbled_usage} ``` rgbled [arguments...] @@ -1345,9 +1169,7 @@ rgbled [arguments...] Source: [drivers/lights/rgbled_is31fl3195](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_is31fl3195) - - -### 사용법 +### Usage {#rgbled_is31fl3195_usage} ``` rgbled_is31fl3195 [arguments...] @@ -1383,9 +1205,7 @@ This used in some GPS modules by Holybro for [PX4 status notification](../gettin The driver is included by default in firmware (KConfig key DRIVERS_LIGHTS_RGBLED_LP5562) and is always enabled. - - -### 사용법 +### Usage {#rgbled_lp5562_usage} ``` rgbled_lp5562 [arguments...] @@ -1426,9 +1246,7 @@ the address `RBCLW_ADDRESS` needs to match the ESC configuration. The command to start this driver is: `$ roboclaw start ` - - -### 사용법 +### Usage {#roboclaw_usage} ``` roboclaw [arguments...] @@ -1444,9 +1262,7 @@ roboclaw [arguments...] Source: [drivers/rpm_capture](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm_capture) - - -### 사용법 +### Usage {#rpm_capture_usage} ``` rpm_capture [arguments...] @@ -1467,9 +1283,7 @@ Source: [drivers/safety_button](https://github.com/PX4/PX4-Autopilot/tree/main/s This module is responsible for the safety button. Pressing the safety button 3 times quickly will trigger a GCS pairing request. - - -### 사용법 +### Usage {#safety_button_usage} ``` safety_button [arguments...] @@ -1481,30 +1295,6 @@ safety_button [arguments...] status print status info ``` -## sbus_rc - -Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) - -### 설명 - -This module does SBUS RC input parsing. - - - -### 사용법 - -``` -sbus_rc [arguments...] - Commands: - start - [-d ] RC device - values: , default: /dev/ttyS3 - - stop - - status print status info -``` - ## septentrio Source: [drivers/gnss/septentrio](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/gnss/septentrio) @@ -1538,9 +1328,7 @@ Perform warm reset of the receivers: gps reset warm ``` - - -### 사용법 +### Usage {#septentrio_usage} ``` septentrio [arguments...] @@ -1573,7 +1361,7 @@ SHT3x Temperature and Humidity Sensor Driver by Senserion. ### 예 -CLI 사용 예: +CLI usage example: ``` sht3x start -X @@ -1599,9 +1387,7 @@ sht3x reset Reinitialize senzor, reset flags - - -### 사용법 +### Usage {#sht3x_usage} ``` sht3x [arguments...] @@ -1640,7 +1426,7 @@ actuator_controls topics, does the mixing and writes the PWM outputs. Currently the module is implemented as a threaded version only, meaning that it runs in its own thread instead of on the work queue. -### 예 +### Example The module is typically started with: @@ -1648,9 +1434,7 @@ The module is typically started with: tap_esc start -d /dev/ttyS2 -n <1-8> ``` - - -### 사용법 +### Usage {#tap_esc_usage} ``` tap_esc [arguments...] @@ -1670,9 +1454,7 @@ Source: [drivers/tone_alarm](https://github.com/PX4/PX4-Autopilot/tree/main/src/ This module is responsible for the tone alarm. - - -### 사용법 +### Usage {#tone_alarm_usage} ``` tone_alarm [arguments...] @@ -1693,7 +1475,7 @@ Source: [drivers/uwb/uwb_sr150](https://github.com/PX4/PX4-Autopilot/tree/main/s Driver for NXP UWB_SR150 UWB positioning system. This driver publishes a `uwb_distance` message whenever the UWB_SR150 has a position measurement available. -### 예 +### Example Start the driver with a given device: @@ -1701,9 +1483,7 @@ Start the driver with a given device: uwb start -d /dev/ttyS2 ``` - - -### 사용법 +### Usage {#uwb_usage} ``` uwb [arguments...] @@ -1723,9 +1503,7 @@ uwb [arguments...] Source: [drivers/actuators/vertiq_io](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/actuators/vertiq_io) - - -### 사용법 +### Usage {#vertiq_io_usage} ``` vertiq_io [arguments...] @@ -1748,9 +1526,7 @@ This module is responsible for driving the output pins. For boards without a sep (eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the px4io driver is used for main ones. - - -### 사용법 +### Usage {#voxl2_io_usage} ``` voxl2_io [arguments...] @@ -1790,9 +1566,7 @@ It is typically started with: todo ``` - - -### 사용법 +### Usage {#voxl_esc_usage} ``` voxl_esc [arguments...] @@ -1839,9 +1613,7 @@ voxl_esc [arguments...] Source: [drivers/power_monitor/voxlpm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/voxlpm) - - -### 사용법 +### Usage {#voxlpm_usage} ``` voxlpm [arguments...] @@ -1871,9 +1643,7 @@ Source: [modules/zenoh](https://github.com/PX4/PX4-Autopilot/tree/main/src/modul Zenoh demo bridge - - -### 사용법 +### Usage {#zenoh_usage} ``` zenoh [arguments...] diff --git a/docs/ko/modules/modules_driver_airspeed_sensor.md b/docs/ko/modules/modules_driver_airspeed_sensor.md index 2dcb3513bb..68738a4053 100644 --- a/docs/ko/modules/modules_driver_airspeed_sensor.md +++ b/docs/ko/modules/modules_driver_airspeed_sensor.md @@ -13,9 +13,7 @@ This is not included by default in firmware. It can be included with terminal co or in default.px4board with adding the line: "CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y" It can be enabled with the "SENS_EN_ASP5033" parameter set to 1. - - -### 사용법 +### Usage {#asp5033_usage} ``` asp5033 [arguments...] @@ -39,9 +37,7 @@ asp5033 [arguments...] Source: [drivers/differential_pressure/auav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/auav) - - -### 사용법 +### Usage {#auav_usage} ``` auav [arguments...] @@ -67,9 +63,7 @@ auav [arguments...] Source: [drivers/differential_pressure/ets](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ets) - - -### 사용법 +### Usage {#ets_airspeed_usage} ``` ets_airspeed [arguments...] @@ -93,9 +87,7 @@ ets_airspeed [arguments...] Source: [drivers/differential_pressure/ms4515](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4515) - - -### 사용법 +### Usage {#ms4515_usage} ``` ms4515 [arguments...] @@ -119,9 +111,7 @@ ms4515 [arguments...] Source: [drivers/differential_pressure/ms4525do](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms4525do) - - -### 사용법 +### Usage {#ms4525do_usage} ``` ms4525do [arguments...] @@ -145,9 +135,7 @@ ms4525do [arguments...] Source: [drivers/differential_pressure/ms5525dso](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/ms5525dso) - - -### 사용법 +### Usage {#ms5525dso_usage} ``` ms5525dso [arguments...] @@ -171,9 +159,7 @@ ms5525dso [arguments...] Source: [drivers/differential_pressure/sdp3x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/sdp3x) - - -### 사용법 +### Usage {#sdp3x_usage} ``` sdp3x [arguments...] diff --git a/docs/ko/modules/modules_driver_baro.md b/docs/ko/modules/modules_driver_baro.md index cf7e7c41cf..b733ebc9d2 100644 --- a/docs/ko/modules/modules_driver_baro.md +++ b/docs/ko/modules/modules_driver_baro.md @@ -4,9 +4,7 @@ Source: [drivers/barometer/bmp280](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp280) - - -### 사용법 +### Usage {#bmp280_usage} ``` bmp280 [arguments...] @@ -42,9 +40,7 @@ bmp280 [arguments...] Source: [drivers/barometer/bmp388](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp388) - - -### 사용법 +### Usage {#bmp388_usage} ``` bmp388 [arguments...] @@ -72,9 +68,7 @@ bmp388 [arguments...] Source: [drivers/barometer/bmp581](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/bmp581) - - -### 사용법 +### Usage {#bmp581_usage} ``` bmp581 [arguments...] @@ -102,9 +96,7 @@ bmp581 [arguments...] Source: [drivers/barometer/dps310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/dps310) - - -### 사용법 +### Usage {#dps310_usage} ``` dps310 [arguments...] @@ -140,9 +132,7 @@ dps310 [arguments...] Source: [drivers/barometer/invensense/icp101xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp101xx) - - -### 사용법 +### Usage {#icp101xx_usage} ``` icp101xx [arguments...] @@ -166,9 +156,7 @@ icp101xx [arguments...] Source: [drivers/barometer/invensense/icp201xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/invensense/icp201xx) - - -### 사용법 +### Usage {#icp201xx_usage} ``` icp201xx [arguments...] @@ -192,9 +180,7 @@ icp201xx [arguments...] Source: [drivers/barometer/lps22hb](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps22hb) - - -### 사용법 +### Usage {#lps22hb_usage} ``` lps22hb [arguments...] @@ -220,9 +206,7 @@ lps22hb [arguments...] Source: [drivers/barometer/lps25h](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps25h) - - -### 사용법 +### Usage {#lps25h_usage} ``` lps25h [arguments...] @@ -248,9 +232,7 @@ lps25h [arguments...] Source: [drivers/barometer/lps33hw](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/lps33hw) - - -### 사용법 +### Usage {#lps33hw_usage} ``` lps33hw [arguments...] @@ -279,9 +261,7 @@ lps33hw [arguments...] Source: [drivers/barometer/maiertek/mpc2520](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/maiertek/mpc2520) - - -### 사용법 +### Usage {#mpc2520_usage} ``` mpc2520 [arguments...] @@ -305,9 +285,7 @@ mpc2520 [arguments...] Source: [drivers/barometer/mpl3115a2](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/mpl3115a2) - - -### 사용법 +### Usage {#mpl3115a2_usage} ``` mpl3115a2 [arguments...] @@ -331,9 +309,7 @@ mpl3115a2 [arguments...] Source: [drivers/barometer/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - - -### 사용법 +### Usage {#ms5611_usage} ``` ms5611 [arguments...] @@ -369,9 +345,7 @@ ms5611 [arguments...] Source: [drivers/barometer/ms5837](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5837) - - -### 사용법 +### Usage {#ms5837_usage} ``` ms5837 [arguments...] @@ -393,9 +367,7 @@ ms5837 [arguments...] Source: [drivers/barometer/goertek/spa06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spa06) - - -### 사용법 +### Usage {#spa06_usage} ``` spa06 [arguments...] @@ -431,9 +403,7 @@ spa06 [arguments...] Source: [drivers/barometer/goertek/spl06](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/goertek/spl06) - - -### 사용법 +### Usage {#spl06_usage} ``` spl06 [arguments...] diff --git a/docs/ko/modules/modules_driver_camera.md b/docs/ko/modules/modules_driver_camera.md index f96bcb68d4..0df0f41a21 100644 --- a/docs/ko/modules/modules_driver_camera.md +++ b/docs/ko/modules/modules_driver_camera.md @@ -34,9 +34,7 @@ In particular: [Setup/usage information](../camera/index.md). - - -### 사용법 +### Usage {#camera_trigger_usage} ``` camera_trigger [arguments...] diff --git a/docs/ko/modules/modules_driver_distance_sensor.md b/docs/ko/modules/modules_driver_distance_sensor.md index 5fc08ae437..59cd62ff91 100644 --- a/docs/ko/modules/modules_driver_distance_sensor.md +++ b/docs/ko/modules/modules_driver_distance_sensor.md @@ -10,21 +10,19 @@ Broadcom AFBRS50용 드라이버입니다. ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` afbrs50 start ``` -드라이버를 중지합니다. +Stop driver ``` afbrs50 stop ``` - - -### 사용법 +### Usage {#afbrs50_usage} ``` afbrs50 [arguments...] @@ -43,9 +41,7 @@ afbrs50 [arguments...] Source: [drivers/distance_sensor/gy_us42](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/gy_us42) - - -### 사용법 +### Usage {#gy_us42_usage} ``` gy_us42 [arguments...] @@ -71,29 +67,27 @@ Source: [drivers/distance_sensor/leddar_one](https://github.com/PX4/PX4-Autopilo ### 설명 -LeddarOne LiDAR 직렬 버스 드라이버입니다. +Serial bus driver for the LeddarOne LiDAR. -대부분의 보드는 SENS_LEDDAR1_CFG 매개변수를 사용하여, 지정된 UART에서 드라이버를 활성화/시작하도록 설정합니다. +Most boards are configured to enable/start the driver on a specified UART using the SENS_LEDDAR1_CFG parameter. Setup/usage information: https://docs.px4.io/main/en/sensor/leddar_one.html ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` leddar_one start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` leddar_one stop ``` - - -### 사용법 +### Usage {#leddar_one_usage} ``` leddar_one [arguments...] @@ -112,13 +106,11 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### 설명 -Lightware SFxx 시리즈 LIDAR 거리 측정기용 I2C 버스 드라이버: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html - - -### 사용법 +### Usage {#lightware_laser_i2c_usage} ``` lightware_laser_i2c [arguments...] @@ -146,29 +138,27 @@ Source: [drivers/distance_sensor/lightware_laser_serial](https://github.com/PX4/ ### 설명 -LightWare SF02/F, SF10/a, SF10/b, SF10/c, SF11/c 레이저 거리 측정기용 직렬 버스 드라이버. +Serial bus driver for the LightWare SF02/F, SF10/a, SF10/b, SF10/c, SF11/c Laser rangefinders. -대부분의 보드는 SENS_SF0X_CFG 매개변수를 사용하여 지정된 UART에서 드라이버를 활성화/시작하도록 설정합니다. +Most boards are configured to enable/start the driver on a specified UART using the SENS_SF0X_CFG parameter. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` lightware_laser_serial start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` lightware_laser_serial stop ``` - - -### 사용법 +### Usage {#lightware_laser_serial_usage} ``` lightware_laser_serial [arguments...] @@ -191,21 +181,19 @@ Serial bus driver for the Lightware SF45/b Laser rangefinder. ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` lightware_sf45_serial start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` lightware_sf45_serial stop ``` - - -### 사용법 +### Usage {#lightware_sf45_serial_usage} ``` lightware_sf45_serial [arguments...] @@ -224,13 +212,11 @@ Source: [drivers/distance_sensor/ll40ls_pwm](https://github.com/PX4/PX4-Autopilo PWM driver for LidarLite rangefinders. -센서/드라이버는 매개변수 SENS_EN_LL40LS를 사용하여 활성화합니다. +The sensor/driver must be enabled using the parameter SENS_EN_LL40LS. Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html - - -### 사용법 +### Usage {#ll40ls_usage} ``` ll40ls [arguments...] @@ -248,9 +234,7 @@ ll40ls [arguments...] Source: [drivers/distance_sensor/mappydot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mappydot) - - -### 사용법 +### Usage {#mappydot_usage} ``` mappydot [arguments...] @@ -272,9 +256,7 @@ mappydot [arguments...] Source: [drivers/distance_sensor/mb12xx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mb12xx) - - -### 사용법 +### Usage {#mb12xx_usage} ``` mb12xx [arguments...] @@ -302,15 +284,17 @@ Source: [drivers/distance_sensor/pga460](https://github.com/PX4/PX4-Autopilot/tr ### 설명 -장치와의 통신을 처리하고, uORB를 통해 거리를 게시하는 초음파 거리 측정기 드라이버입니다. +Ultrasonic range finder driver that handles the communication with the device and publishes the distance via uORB. ### 구현 -This driver is implemented as a NuttX task. 이 구현은 work_queue에서 지원되지 않는 UART를 통해 메시지에 대한 폴링이 필요하기 때문에 선택되었습니다. 이 드라이버는 실행되는 동안 지속적으로 범위 측정을 수행합니다. 잘못된 판독값을 감지하는 간단한 알고리즘은 게시중인 데이터의 품질을 개선하기 위하여 드라이버 수준에서 구현됩니다. 드라이버는 센서 데이터가 유효하지 않거나 불안정하다고 판단되는 경우에는, 데이터를 게시하지 않습니다. +This driver is implemented as a NuttX task. This Implementation was chosen due to the need for polling on a message +via UART, which is not supported in the work_queue. This driver continuously takes range measurements while it is +running. A simple algorithm to detect false readings is implemented at the driver levelin an attemptto improve +the quality of data that is being published. The driver will not publish data at all if it deems the sensor data +to be invalid or unstable. - - -### 사용법 +### Usage {#pga460_usage} ``` pga460 [arguments...] @@ -329,9 +313,7 @@ pga460 [arguments...] Source: [drivers/distance_sensor/srf02](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/srf02) - - -### 사용법 +### Usage {#srf02_usage} ``` srf02 [arguments...] @@ -359,13 +341,11 @@ Source: [drivers/distance_sensor/srf05](https://github.com/PX4/PX4-Autopilot/tre ### 설명 -HY-SRF05 / HC-SR05 및 HC-SR04 거리 측정기용 드라이버입니다. +Driver for HY-SRF05 / HC-SR05 and HC-SR04 rangefinders. -센서/드라이버는 SENS_EN_HXSRX0X 매개변수를 사용하여 활성화합니다. +The sensor/driver must be enabled using the parameter SENS_EN_HXSRX0X. - - -### 사용법 +### Usage {#srf05_usage} ``` srf05 [arguments...] @@ -389,15 +369,13 @@ Source: [drivers/distance_sensor/teraranger](https://github.com/PX4/PX4-Autopilo ### 설명 -TeraRanger 거리 측정기를 위한 I2C 버스 드라이버입니다. +I2C bus driver for TeraRanger rangefinders. -센서/드라이버는 SENS_EN_TRANGER 매개변수를 사용하여 활성화합니다. +The sensor/driver must be enabled using the parameter SENS_EN_TRANGER. Setup/usage information: https://docs.px4.io/main/en/sensor/rangefinders.html#teraranger-rangefinders - - -### 사용법 +### Usage {#teraranger_usage} ``` teraranger [arguments...] @@ -423,9 +401,7 @@ teraranger [arguments...] Source: [drivers/distance_sensor/tf02pro](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/tf02pro) - - -### 사용법 +### Usage {#tf02pro_usage} ``` tf02pro [arguments...] @@ -453,29 +429,27 @@ Source: [drivers/distance_sensor/tfmini](https://github.com/PX4/PX4-Autopilot/tr ### 설명 -Benewake TFmini LiDAR용 직렬 버스 드라이버입니다. +Serial bus driver for the Benewake TFmini LiDAR. -대부분의 보드는 SENS_TFMINI_CFG 매개변수를 사용하여 지정된 UART에서 드라이버를 활성화/시작하도록 설정합니다. +Most boards are configured to enable/start the driver on a specified UART using the SENS_TFMINI_CFG parameter. Setup/usage information: https://docs.px4.io/main/en/sensor/tfmini.html ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` tfmini start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` tfmini stop ``` - - -### 사용법 +### Usage {#tfmini_usage} ``` tfmini [arguments...] @@ -498,27 +472,25 @@ Source: [drivers/distance_sensor/ulanding_radar](https://github.com/PX4/PX4-Auto ### 설명 -Aerotenna uLanding 레이더용 직렬 버스 드라이버입니다. +Serial bus driver for the Aerotenna uLanding radar. Setup/usage information: https://docs.px4.io/main/en/sensor/ulanding_radar.html ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` ulanding_radar start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` ulanding_radar stop ``` - - -### 사용법 +### Usage {#ulanding_radar_usage} ``` ulanding_radar [arguments...] @@ -536,9 +508,7 @@ ulanding_radar [arguments...] Source: [drivers/distance_sensor/vl53l0x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l0x) - - -### 사용법 +### Usage {#vl53l0x_usage} ``` vl53l0x [arguments...] @@ -564,9 +534,7 @@ vl53l0x [arguments...] Source: [drivers/distance_sensor/vl53l1x](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/vl53l1x) - - -### 사용법 +### Usage {#vl53l1x_usage} ``` vl53l1x [arguments...] diff --git a/docs/ko/modules/modules_driver_imu.md b/docs/ko/modules/modules_driver_imu.md index 6de55d0443..cc58388343 100644 --- a/docs/ko/modules/modules_driver_imu.md +++ b/docs/ko/modules/modules_driver_imu.md @@ -4,9 +4,7 @@ Source: [drivers/imu/analog_devices/adis16448](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16448) - - -### 사용법 +### Usage {#adis16448_usage} ``` adis16448 [arguments...] @@ -32,9 +30,7 @@ adis16448 [arguments...] Source: [drivers/imu/analog_devices/adis16470](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16470) - - -### 사용법 +### Usage {#adis16470_usage} ``` adis16470 [arguments...] @@ -60,9 +56,7 @@ adis16470 [arguments...] Source: [drivers/imu/analog_devices/adis16477](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16477) - - -### 사용법 +### Usage {#adis16477_usage} ``` adis16477 [arguments...] @@ -88,9 +82,7 @@ adis16477 [arguments...] Source: [drivers/imu/analog_devices/adis16497](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16497) - - -### 사용법 +### Usage {#adis16497_usage} ``` adis16497 [arguments...] @@ -116,9 +108,7 @@ adis16497 [arguments...] Source: [drivers/imu/analog_devices/adis16507](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/analog_devices/adis16507) - - -### 사용법 +### Usage {#adis16507_usage} ``` adis16507 [arguments...] @@ -144,9 +134,7 @@ adis16507 [arguments...] Source: [drivers/imu/bosch/bmi055](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi055) - - -### 사용법 +### Usage {#bmi055_usage} ``` bmi055 [arguments...] @@ -174,9 +162,7 @@ bmi055 [arguments...] Source: [drivers/imu/bosch/bmi085](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi085) - - -### 사용법 +### Usage {#bmi085_usage} ``` bmi085 [arguments...] @@ -204,9 +190,7 @@ bmi085 [arguments...] Source: [drivers/imu/bosch/bmi088](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088) - - -### 사용법 +### Usage {#bmi088_usage} ``` bmi088 [arguments...] @@ -234,9 +218,7 @@ bmi088 [arguments...] Source: [drivers/imu/bosch/bmi088_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi088_i2c) - - -### 사용법 +### Usage {#bmi088_i2c_usage} ``` bmi088_i2c [arguments...] @@ -264,9 +246,7 @@ bmi088_i2c [arguments...] Source: [drivers/imu/bosch/bmi270](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/bosch/bmi270) - - -### 사용법 +### Usage {#bmi270_usage} ``` bmi270 [arguments...] @@ -292,9 +272,7 @@ bmi270 [arguments...] Source: [drivers/imu/nxp/fxas21002c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxas21002c) - - -### 사용법 +### Usage {#fxas21002c_usage} ``` fxas21002c [arguments...] @@ -328,9 +306,7 @@ fxas21002c [arguments...] Source: [drivers/imu/nxp/fxos8701cq](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/nxp/fxos8701cq) - - -### 사용법 +### Usage {#fxos8701cq_usage} ``` fxos8701cq [arguments...] @@ -364,9 +340,7 @@ fxos8701cq [arguments...] Source: [drivers/imu/invensense/iam20680hp](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iam20680hp) - - -### 사용법 +### Usage {#iam20680hp_usage} ``` iam20680hp [arguments...] @@ -392,9 +366,7 @@ iam20680hp [arguments...] Source: [drivers/imu/invensense/icm20602](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20602) - - -### 사용법 +### Usage {#icm20602_usage} ``` icm20602 [arguments...] @@ -420,9 +392,7 @@ icm20602 [arguments...] Source: [drivers/imu/invensense/icm20608g](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20608g) - - -### 사용법 +### Usage {#icm20608g_usage} ``` icm20608g [arguments...] @@ -448,9 +418,7 @@ icm20608g [arguments...] Source: [drivers/imu/invensense/icm20649](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20649) - - -### 사용법 +### Usage {#icm20649_usage} ``` icm20649 [arguments...] @@ -476,9 +444,7 @@ icm20649 [arguments...] Source: [drivers/imu/invensense/icm20689](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20689) - - -### 사용법 +### Usage {#icm20689_usage} ``` icm20689 [arguments...] @@ -504,9 +470,7 @@ icm20689 [arguments...] Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - - -### 사용법 +### Usage {#icm20948_usage} ``` icm20948 [arguments...] @@ -533,9 +497,7 @@ icm20948 [arguments...] Source: [drivers/imu/invensense/icm20948](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm20948) - - -### 사용법 +### Usage {#icm20948_i2c_passthrough_usage} ``` icm20948_i2c_passthrough [arguments...] @@ -559,9 +521,7 @@ icm20948_i2c_passthrough [arguments...] Source: [drivers/imu/invensense/icm40609d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm40609d) - - -### 사용법 +### Usage {#icm40609d_usage} ``` icm40609d [arguments...] @@ -587,9 +547,7 @@ icm40609d [arguments...] Source: [drivers/imu/invensense/icm42605](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42605) - - -### 사용법 +### Usage {#icm42605_usage} ``` icm42605 [arguments...] @@ -611,13 +569,11 @@ icm42605 [arguments...] status print status info ``` -## icm42688p +## icm42670p Source: [drivers/imu/invensense/icm42670p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42670p) - - -### 사용법 +### Usage {#icm42670p_usage} ``` icm42670p [arguments...] @@ -639,13 +595,11 @@ icm42670p [arguments...] status print status info ``` -## l3gd20 +## icm42688p Source: [drivers/imu/invensense/icm42688p](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm42688p) - - -### 사용법 +### Usage {#icm42688p_usage} ``` icm42688p [arguments...] @@ -674,9 +628,7 @@ icm42688p [arguments...] Source: [drivers/imu/invensense/icm45686](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/icm45686) - - -### 사용법 +### Usage {#icm45686_usage} ``` icm45686 [arguments...] @@ -704,9 +656,7 @@ icm45686 [arguments...] Source: [drivers/imu/invensense/iim42652](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42652) - - -### 사용법 +### Usage {#iim42652_usage} ``` iim42652 [arguments...] @@ -734,9 +684,7 @@ iim42652 [arguments...] Source: [drivers/imu/invensense/iim42653](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/iim42653) - - -### 사용법 +### Usage {#iim42653_usage} ``` iim42653 [arguments...] @@ -760,13 +708,11 @@ iim42653 [arguments...] status print status info ``` -## lsm303d +## l3gd20 Source: [drivers/imu/st/l3gd20](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/l3gd20) - - -### 사용법 +### Usage {#l3gd20_usage} ``` l3gd20 [arguments...] @@ -792,13 +738,11 @@ l3gd20 [arguments...] status print status info ``` -## lsm9ds1 +## lsm303d Source: [drivers/imu/st/lsm303d](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm303d) - - -### 사용법 +### Usage {#lsm303d_usage} ``` lsm303d [arguments...] @@ -820,13 +764,11 @@ lsm303d [arguments...] status print status info ``` -## mpu6000 +## lsm9ds1 Source: [drivers/imu/st/lsm9ds1](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/st/lsm9ds1) - - -### 사용법 +### Usage {#lsm9ds1_usage} ``` lsm9ds1 [arguments...] @@ -848,13 +790,11 @@ lsm9ds1 [arguments...] status print status info ``` -## mpu9520 +## mpu6000 Source: [drivers/imu/invensense/mpu6000](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6000) - - -### 사용법 +### Usage {#mpu6000_usage} ``` mpu6000 [arguments...] @@ -880,9 +820,7 @@ mpu6000 [arguments...] Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - - -### 사용법 +### Usage {#mpu9250_usage} ``` mpu9250 [arguments...] @@ -909,9 +847,7 @@ mpu9250 [arguments...] Source: [drivers/imu/invensense/mpu9250](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu9250) - - -### 사용법 +### Usage {#mpu9250_i2c_usage} ``` mpu9250_i2c [arguments...] @@ -933,13 +869,11 @@ mpu9250_i2c [arguments...] status print status info ``` -## mpu9520_i2c +## mpu9520 Source: [drivers/imu/invensense/mpu6500](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/invensense/mpu6500) - - -### 사용법 +### Usage {#mpu9520_usage} ``` mpu9520 [arguments...] @@ -965,9 +899,7 @@ mpu9520 [arguments...] Source: [drivers/imu/murata/sch16t](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/imu/murata/sch16t) - - -### 사용법 +### Usage {#sch16t_usage} ``` sch16t [arguments...] diff --git a/docs/ko/modules/modules_driver_ins.md b/docs/ko/modules/modules_driver_ins.md index 37d6a96932..514d508c49 100644 --- a/docs/ko/modules/modules_driver_ins.md +++ b/docs/ko/modules/modules_driver_ins.md @@ -14,21 +14,19 @@ Setup/usage information: https://docs.px4.io/main/en/sensor/vectornav.html ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` vectornav start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` vectornav stop ``` - - -### 사용법 +### Usage {#vectornav_usage} ``` vectornav [arguments...] diff --git a/docs/ko/modules/modules_driver_magnetometer.md b/docs/ko/modules/modules_driver_magnetometer.md index 677103359b..9a42d8f39a 100644 --- a/docs/ko/modules/modules_driver_magnetometer.md +++ b/docs/ko/modules/modules_driver_magnetometer.md @@ -4,9 +4,7 @@ Source: [drivers/magnetometer/akm/ak09916](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak09916) - - -### 사용법 +### Usage {#ak09916_usage} ``` ak09916 [arguments...] @@ -32,9 +30,7 @@ ak09916 [arguments...] Source: [drivers/magnetometer/akm/ak8963](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/akm/ak8963) - - -### 사용법 +### Usage {#ak8963_usage} ``` ak8963 [arguments...] @@ -60,9 +56,7 @@ ak8963 [arguments...] Source: [drivers/magnetometer/bosch/bmm150](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm150) - - -### 사용법 +### Usage {#bmm150_usage} ``` bmm150 [arguments...] @@ -88,9 +82,7 @@ bmm150 [arguments...] Source: [drivers/magnetometer/bosch/bmm350](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/bosch/bmm350) - - -### 사용법 +### Usage {#bmm350_usage} ``` bmm350 [arguments...] @@ -116,9 +108,7 @@ bmm350 [arguments...] Source: [drivers/magnetometer/hmc5883](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/hmc5883) - - -### 사용법 +### Usage {#hmc5883_usage} ``` hmc5883 [arguments...] @@ -147,9 +137,7 @@ hmc5883 [arguments...] Source: [drivers/magnetometer/st/iis2mdc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/st/iis2mdc) - - -### 사용법 +### Usage {#iis2mdc_usage} ``` iis2mdc [arguments...] @@ -173,9 +161,7 @@ iis2mdc [arguments...] Source: [drivers/magnetometer/isentek/ist8308](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8308) - - -### 사용법 +### Usage {#ist8308_usage} ``` ist8308 [arguments...] @@ -201,9 +187,7 @@ ist8308 [arguments...] Source: [drivers/magnetometer/isentek/ist8310](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/isentek/ist8310) - - -### 사용법 +### Usage {#ist8310_usage} ``` ist8310 [arguments...] @@ -229,9 +213,7 @@ ist8310 [arguments...] Source: [drivers/magnetometer/lis3mdl](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lis3mdl) - - -### 사용법 +### Usage {#lis3mdl_usage} ``` lis3mdl [arguments...] @@ -263,9 +245,7 @@ lis3mdl [arguments...] Source: [drivers/magnetometer/lsm9ds1_mag](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/lsm9ds1_mag) - - -### 사용법 +### Usage {#lsm9ds1_mag_usage} ``` lsm9ds1_mag [arguments...] @@ -291,9 +271,7 @@ lsm9ds1_mag [arguments...] Source: [drivers/magnetometer/memsic/mmc5983ma](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/memsic/mmc5983ma) - - -### 사용법 +### Usage {#mmc5983ma_usage} ``` mmc5983ma [arguments...] @@ -325,9 +303,7 @@ mmc5983ma [arguments...] Source: [drivers/magnetometer/qmc5883l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/qmc5883l) - - -### 사용법 +### Usage {#qmc5883l_usage} ``` qmc5883l [arguments...] @@ -353,9 +329,7 @@ qmc5883l [arguments...] Source: [drivers/magnetometer/rm3100](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/rm3100) - - -### 사용법 +### Usage {#rm3100_usage} ``` rm3100 [arguments...] @@ -383,9 +357,7 @@ rm3100 [arguments...] Source: [drivers/magnetometer/vtrantech/vcm1193l](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/magnetometer/vtrantech/vcm1193l) - - -### 사용법 +### Usage {#vcm1193l_usage} ``` vcm1193l [arguments...] diff --git a/docs/ko/modules/modules_driver_optical_flow.md b/docs/ko/modules/modules_driver_optical_flow.md index f9a553fb2e..4da91ab59c 100644 --- a/docs/ko/modules/modules_driver_optical_flow.md +++ b/docs/ko/modules/modules_driver_optical_flow.md @@ -14,21 +14,19 @@ Setup/usage information: https://docs.px4.io/main/en/sensor/pmw3901.html#thone-t ### 예 -지정된 직렬 장치에서 드라이버를 시작하려고 합니다. +Attempt to start driver on a specified serial device. ``` thoneflow start -d /dev/ttyS1 ``` -드라이버를 중지합니다. +Stop driver ``` thoneflow stop ``` - - -### 사용법 +### Usage {#thoneflow_usage} ``` thoneflow [arguments...] diff --git a/docs/ko/modules/modules_driver_radio_control.md b/docs/ko/modules/modules_driver_radio_control.md new file mode 100644 index 0000000000..c226610884 --- /dev/null +++ b/docs/ko/modules/modules_driver_radio_control.md @@ -0,0 +1,122 @@ +# Modules Reference: Radio Control (Driver) + +## crsf_rc + +Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc) + +### 설명 + +This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data + +### Usage {#crsf_rc_usage} + +``` +crsf_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## dsm_rc + +Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc) + +### 설명 + +This module does Spektrum DSM RC input parsing. + +### Usage {#dsm_rc_usage} + +``` +dsm_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## ghst_rc + +Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc) + +### 설명 + +This module does Ghost (GHST) RC input parsing. + +### Usage {#ghst_rc_usage} + +``` +ghst_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` + +## rc_input + +Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input) + +### 설명 + +This module does the RC input parsing and auto-selecting the method. Supported methods are: + +- PPM +- SBUS +- DSM +- SUMD +- ST24 +- TBS Crossfire (CRSF) + +### Usage {#rc_input_usage} + +``` +rc_input [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + bind Send a DSM bind command (module must be running) + + stop + + status print status info +``` + +## sbus_rc + +Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc) + +### 설명 + +This module does SBUS RC input parsing. + +### Usage {#sbus_rc_usage} + +``` +sbus_rc [arguments...] + Commands: + start + [-d ] RC device + values: , default: /dev/ttyS3 + + stop + + status print status info +``` diff --git a/docs/ko/modules/modules_driver_rpm_sensor.md b/docs/ko/modules/modules_driver_rpm_sensor.md index e43c059e5a..b4d7b95243 100644 --- a/docs/ko/modules/modules_driver_rpm_sensor.md +++ b/docs/ko/modules/modules_driver_rpm_sensor.md @@ -4,9 +4,7 @@ Source: [drivers/rpm/pcf8583](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rpm/pcf8583) - - -### 사용법 +### Usage {#pcf8583_usage} ``` pcf8583 [arguments...] diff --git a/docs/ko/modules/modules_driver_transponder.md b/docs/ko/modules/modules_driver_transponder.md index e88a4b9d2b..cd9e77ee03 100644 --- a/docs/ko/modules/modules_driver_transponder.md +++ b/docs/ko/modules/modules_driver_transponder.md @@ -24,9 +24,7 @@ Set the Squawk Code $ sagetech_mxs squawk 1200 ``` - - -### 사용법 +### Usage {#sagetech_mxs_usage} ``` sagetech_mxs [arguments...] diff --git a/docs/ko/modules/modules_estimator.md b/docs/ko/modules/modules_estimator.md index febcd5b688..c4f57f3fff 100644 --- a/docs/ko/modules/modules_estimator.md +++ b/docs/ko/modules/modules_estimator.md @@ -8,9 +8,7 @@ Source: [modules/attitude_estimator_q](https://github.com/PX4/PX4-Autopilot/tree 자세 추정자 Q입니다. - - -### 사용법 +### Usage {#AttitudeEstimatorQ_usage} ``` AttitudeEstimatorQ [arguments...] @@ -31,9 +29,7 @@ Source: [modules/airspeed_selector](https://github.com/PX4/PX4-Autopilot/tree/ma 이 모듈은 표시(IAS), 보정(CAS), 실제 속도(TAS) 및 추정이 현재 유효하지 않은 경우와 기반 센서 판독값 또는 지상 속도에서 풍속을 뺀 경우 정보를 포함하는 단일 airspeed_validated 주제를 제공합니다. 다중 "원시" 속도 입력을 지원하는 이 모듈은 오류 감지시 자동으로 유효한 센서로 전환합니다. 고장 감지와 IAS에서 CAS까지의 축척 계수 추정을 위하여 여러 바람 추정기를 실행하고 이를 게시합니다. - - -### 사용법 +### Usage {#airspeed_estimator_usage} ``` airspeed_estimator [arguments...] @@ -58,9 +54,7 @@ The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.p ekf2 can be started in replay mode (`-r`): in this mode, it does not access the system time, but only uses the timestamps from the sensor topics. - - -### 사용법 +### Usage {#ekf2_usage} ``` ekf2 [arguments...] @@ -85,9 +79,7 @@ Source: [modules/local_position_estimator](https://github.com/PX4/PX4-Autopilot/ 확장 칼만 필터를 사용한 태도 및 위치 추정기입니다. - - -### 사용법 +### Usage {#local_position_estimator_usage} ``` local_position_estimator [arguments...] @@ -105,9 +97,7 @@ Source: [modules/mc_hover_thrust_estimator](https://github.com/PX4/PX4-Autopilot ### 설명 - - -### 사용법 +### Usage {#mc_hover_thrust_estimator_usage} ``` mc_hover_thrust_estimator [arguments...] diff --git a/docs/ko/modules/modules_simulation.md b/docs/ko/modules/modules_simulation.md index cb6164dabd..f2e4bccb89 100644 --- a/docs/ko/modules/modules_simulation.md +++ b/docs/ko/modules/modules_simulation.md @@ -21,9 +21,7 @@ signals given by the control allocation module. 적분에는 순방향 오일러가 사용됩니다. 대부분의 변수는 스택 오버플로를 피하기 위하여 .hpp 파일에서 전역으로 선언됩니다. - - -### 사용법 +### Usage {#simulator_sih_usage} ``` simulator_sih [arguments...] diff --git a/docs/ko/modules/modules_system.md b/docs/ko/modules/modules_system.md index 7020a880ce..e621beca92 100644 --- a/docs/ko/modules/modules_system.md +++ b/docs/ko/modules/modules_system.md @@ -6,9 +6,7 @@ Source: [modules/simulation/battery_simulator](https://github.com/PX4/PX4-Autopi ### 설명 - - -### 사용법 +### Usage {#battery_simulator_usage} ``` battery_simulator [arguments...] @@ -26,17 +24,15 @@ Source: [modules/battery_status](https://github.com/PX4/PX4-Autopilot/tree/main/ ### 설명 -제공 기능은 다음과 같습니다: +The provided functionality includes: - Read the output from the ADC driver (via ioctl interface) and publish `battery_status`. ### 구현 -자체 스레드에서 실행되고, 현재 선택된 자이로 주제를 폴링합니다. +It runs in its own thread and polls on the currently selected gyro topic. - - -### 사용법 +### Usage {#battery_status_usage} ``` battery_status [arguments...] @@ -74,9 +70,7 @@ It discards topics from the `camera_trigger` module if camera capture is enabled For the topics that are not discarded it creates a `CameraCapture` topic with the timestamp information from the `CameraTrigger` and position information from the vehicle. - - -### 사용법 +### Usage {#camera_feedback_usage} ``` camera_feedback [arguments...] @@ -99,9 +93,7 @@ The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin and continue to check for VBUS and start mavlink once it is detected. - - -### 사용법 +### Usage {#cdcacm_autostart_usage} ``` cdcacm_autostart [arguments...] @@ -119,11 +111,9 @@ Source: [modules/commander](https://github.com/PX4/PX4-Autopilot/tree/main/src/m ### 설명 -커맨더 모듈에는 모드 전환 및 안전 장치 동작을 위한 상태 머신이 포함되어 있습니다. +The commander module contains the state machine for mode switching and failsafe behavior. - - -### 사용법 +### Usage {#commander_usage} ``` commander [arguments...] @@ -177,22 +167,20 @@ Source: [modules/dataman](https://github.com/PX4/PX4-Autopilot/tree/main/src/mod ### 설명 -C API를 통해 간단한 데이터베이스 형태로 시스템에 영구 저장소를 제공하는 모듈입니다. +Module to provide persistent storage for the rest of the system in form of a simple database through a C API. Multiple backends are supported depending on the board: -- 파일(예: SD 카드) -- RAM (영구적이지 않음) +- a file (eg. on the SD card) +- RAM (this is obviously not persistent) -임무 웨이포인트, 임무 상태 및 지오펜스 다각형과 같은 다양한 유형의 구조화된 데이터를 저장합니다. -각 유형은 특정 유형과 고정된 최대 저장 항목 수를 가지고 있어, 빠른 랜덤 액세스가 가능합니다. +It is used to store structured data of different types: mission waypoints, mission state and geofence polygons. +Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible. ### 구현 -단일 항목을 읽고 쓰는 것은 항상 원자적입니다. +Reading and writing a single item is always atomic. - - -### 사용법 +### Usage {#dataman_usage} ``` dataman [arguments...] @@ -216,20 +204,18 @@ Source: [systemcmds/dmesg](https://github.com/PX4/PX4-Autopilot/tree/main/src/sy ### 설명 -부팅 콘솔 메시지를 출력합니다. -NuttX의 작업 대기열 및 syslog의 출력은 캡처되지 않습니다. +Command-line tool to show bootup console messages. +Note that output from NuttX's work queues and syslog are not captured. ### 예 -백그라운드에서 모든 메시지를 출력합니다. +Keep printing all messages in the background: ``` dmesg -f & ``` - - -### 사용법 +### Usage {#dmesg_usage} ``` dmesg [arguments...] @@ -243,11 +229,9 @@ Source: [modules/esc_battery](https://github.com/PX4/PX4-Autopilot/tree/main/src ### 설명 -ESC 상태의 정보를 사용하여 구현하고, 배터리 상태를 게시합니다. +This implements using information from the ESC status and publish it as battery status. - - -### 사용법 +### Usage {#esc_battery_usage} ``` esc_battery [arguments...] @@ -265,11 +249,9 @@ Source: [modules/gyro_calibration](https://github.com/PX4/PX4-Autopilot/tree/mai ### 설명 -간단한 온라인 자이로스코프 교정. +Simple online gyroscope calibration. - - -### 사용법 +### Usage {#gyro_calibration_usage} ``` gyro_calibration [arguments...] @@ -287,9 +269,7 @@ Source: [modules/gyro_fft](https://github.com/PX4/PX4-Autopilot/tree/main/src/mo ### 설명 - - -### 사용법 +### Usage {#gyro_fft_usage} ``` gyro_fft [arguments...] @@ -307,13 +287,11 @@ Source: [drivers/heater](https://github.com/PX4/PX4-Autopilot/tree/main/src/driv ### 설명 -설정점에서 IMU 온도를 조절하기 위하여 LP 작업 대기열에서 주기적으로 실행되는 백그라운드 프로세스입니다. +Background process running periodically on the LP work queue to regulate IMU temperature at a setpoint. -이 작업은 부팅 시 SENS_EN_THERMAL을 설정하거나, CLI를 통하여 시작 스크립트에서 시작할 수 있습니다. +This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI. - - -### 사용법 +### Usage {#heater_usage} ``` heater [arguments...] @@ -333,9 +311,7 @@ Source: [systemcmds/i2c_launcher](https://github.com/PX4/PX4-Autopilot/tree/main Daemon that starts drivers based on found I2C devices. - - -### 사용법 +### Usage {#i2c_launcher_usage} ``` i2c_launcher [arguments...] @@ -401,9 +377,7 @@ The architecture is as shown below: - - -### 사용법 +### Usage {#internal_combustion_engine_control_usage} ``` internal_combustion_engine_control [arguments...] @@ -427,23 +401,25 @@ states, such as commanded thrust, arming state and vehicle motion. ### 구현 -모든 유형은 공통 기본 클래스를 사용하여 자체 클래스에서 구현됩니다. 기본 클래스는 상태를 유지합니다(착륙, 아마도_착륙, 지상_접촉). 가능한 각 상태는 파생 클래스에서 구현됩니다. 각 내부 상태의 히스테리시스 및 고정된 우선 순위에 따라 실제 land_detector 상태가 결정됩니다. +Every type is implemented in its own class with a common base class. The base class maintains a state (landed, +maybe_landed, ground_contact). Each possible state is implemented in the derived classes. A hysteresis and a fixed +priority of each internal state determines the actual land_detector state. -#### 멀티콥터 착륙 감지기 +#### Multicopter Land Detector **ground_contact**: thrust setpoint and velocity in z-direction must be below a defined threshold for time -GROUND_CONTACT_TRIGGER_TIME_US. ground_contact가 감지되면, 위치 컨트롤러는 본체 x 및 y의 추력 설정값을 끕니다. +GROUND_CONTACT_TRIGGER_TIME_US. When ground_contact is detected, the position controller turns off the thrust setpoint +in body x and y. **maybe_landed**: it requires ground_contact together with a tighter thrust setpoint threshold and no velocity in the -horizontal direction. 트리거 시간은 MAYBE_LAND_TRIGGER_TIME에 의해 정의됩니다. Maybe_landed가 감지되면 위치 컨트롤러는 추력 설정값을 0으로 설정합니다. +horizontal direction. The trigger time is defined by MAYBE_LAND_TRIGGER_TIME. When maybe_landed is detected, the +position controller sets the thrust setpoint to zero. **landed**: it requires maybe_landed to be true for time LAND_DETECTOR_TRIGGER_TIME_US. -모듈은 HP 작업 대기열에서 주기적으로 실행됩니다. +The module runs periodically on the HP work queue. - - -### 사용법 +### Usage {#land_detector_usage} ``` land_detector [arguments...] @@ -465,11 +441,10 @@ Source: [modules/load_mon](https://github.com/PX4/PX4-Autopilot/tree/main/src/mo Background process running periodically on the low priority work queue to calculate the CPU load and RAM usage and publish the `cpuload` topic. -NuttX에서는 각 프로세스의 스택 사용량도 확인하고, 300바이트 미만으로 떨어지면 경고가 출력되고 로그 파일에도 기록됩니다. +On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output, +which will also appear in the log file. - - -### 사용법 +### Usage {#load_mon_usage} ``` load_mon [arguments...] @@ -488,45 +463,47 @@ Source: [modules/logger](https://github.com/PX4/PX4-Autopilot/tree/main/src/modu ### 설명 System logger which logs a configurable set of uORB topics and system printf messages -(`PX4_WARN` and `PX4_ERR`) to ULog files. 시스템 및 비행 성능 평가, 튜닝, 재생 및 충돌 분석에 사용할 수 있습니다. +(`PX4_WARN` and `PX4_ERR`) to ULog files. These can be used for system and flight performance evaluation, +tuning, replay and crash analysis. -2개의 백엔드를 지원합니다. +It supports 2 backends: -- 파일: ULog 파일을 파일 시스템(SD 카드)에 기록합니다. -- MAVLink: MAVLink를 통해 ULog 데이터를 클라이언트로 스트리밍합니다(클라이언트가 이를 지원해야 함). +- Files: write ULog files to the file system (SD card) +- MAVLink: stream ULog data via MAVLink to a client (the client must support this) -두 백엔드를 동시에 활성화하고 사용할 수 있습니다. +Both backends can be enabled and used at the same time. -파일 백엔드는 전체(일반 로그)와 미션 로그의 두 가지 유형의 로그 파일을 지원합니다. 임무 로그는 축소된 ulog 파일이며, 지오태깅 또는 차량 관리 등에 사용할 수 있습니다. SDLOG_MISSION 매개변수를 통하여 활성화 및 설정할 수 있습니다. -일반 로그는 항상 미션 로그의 상위 집합입니다. +The file backend supports 2 types of log files: full (the normal log) and a mission +log. The mission log is a reduced ulog file and can be used for example for geotagging or +vehicle management. It can be enabled and configured via SDLOG_MISSION parameter. +The normal log is always a superset of the mission log. ### 구현 -구현은 두 개의 스레드를 사용합니다. +The implementation uses two threads: - The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for data updates -- 작성자 스레드, 파일에 데이터 쓰기 +- The writer thread, writing data to the file -그 사이에는 구성 가능한 크기의 쓰기 버퍼가 있습니다(및 미션 로그를 위한 또 다른 고정 크기 버퍼). 드롭아웃을 방지하려면 크기가 커야 합니다. +In between there is a write buffer with configurable size (and another fixed-size buffer for +the mission log). It should be large to avoid dropouts. ### 예 -즉시 로깅을 시작하는 일반적인 사용법입니다. +Typical usage to start logging immediately: ``` logger start -e -t ``` -또는, 이미 동작중일 경우 +Or if already running: ``` logger on ``` - - -### 사용법 +### Usage {#logger_usage} ``` logger [arguments...] @@ -561,7 +538,7 @@ logger [arguments...] status print status info ``` -## netman +## mag_bias_estimator Source: [modules/mag_bias_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mag_bias_estimator) @@ -569,9 +546,7 @@ Source: [modules/mag_bias_estimator](https://github.com/PX4/PX4-Autopilot/tree/m Online magnetometer bias estimator. - - -### 사용법 +### Usage {#mag_bias_estimator_usage} ``` mag_bias_estimator [arguments...] @@ -583,7 +558,7 @@ mag_bias_estimator [arguments...] status print status info ``` -## pwm_input +## manual_control Source: [modules/manual_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/manual_control) @@ -591,9 +566,7 @@ Source: [modules/manual_control](https://github.com/PX4/PX4-Autopilot/tree/main/ Module consuming manual_control_inputs publishing one manual_control_setpoint. - - -### 사용법 +### Usage {#manual_control_usage} ``` manual_control [arguments...] @@ -641,9 +614,7 @@ $ netman save # Save the parameters to the SD card. $ netman show # display current settings. $ netman update -i eth0 # do an update - - -### 사용법 +### Usage {#netman_usage} ``` netman [arguments...] @@ -666,9 +637,7 @@ Source: [drivers/pwm_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/d Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input\` message. - - -### 사용법 +### Usage {#pwm_input_usage} ``` pwm_input [arguments...] @@ -694,9 +663,7 @@ and then publish as `rc_channels` and `manual_control_input`. To reduce control latency, the module is scheduled on input_rc publications. - - -### 사용법 +### Usage {#rc_update_usage} ``` rc_update [arguments...] @@ -731,9 +698,7 @@ the log. The replay procedure is documented on the [System-wide Replay](https://docs.px4.io/main/en/debug/system_wide_replay.html) page. - - -### 사용법 +### Usage {#replay_usage} ``` replay [arguments...] @@ -760,9 +725,7 @@ It is currently only responsible for tone alarm on RC Loss. The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.). - - -### 사용법 +### Usage {#send_event_usage} ``` send_event [arguments...] @@ -782,9 +745,7 @@ Source: [modules/simulation/sensor_agp_sim](https://github.com/PX4/PX4-Autopilot Module to simulate auxiliary global position measurements with optional failure modes for SIH simulation. - - -### 사용법 +### Usage {#sensor_agp_sim_usage} ``` sensor_agp_sim [arguments...] @@ -802,9 +763,7 @@ Source: [modules/simulation/sensor_airspeed_sim](https://github.com/PX4/PX4-Auto ### 설명 - - -### 사용법 +### Usage {#sensor_arispeed_sim_usage} ``` sensor_arispeed_sim [arguments...] @@ -822,9 +781,7 @@ Source: [modules/simulation/sensor_baro_sim](https://github.com/PX4/PX4-Autopilo ### 설명 - - -### 사용법 +### Usage {#sensor_baro_sim_usage} ``` sensor_baro_sim [arguments...] @@ -842,9 +799,7 @@ Source: [modules/simulation/sensor_gps_sim](https://github.com/PX4/PX4-Autopilot ### 설명 - - -### 사용법 +### Usage {#sensor_gps_sim_usage} ``` sensor_gps_sim [arguments...] @@ -862,9 +817,7 @@ Source: [modules/simulation/sensor_mag_sim](https://github.com/PX4/PX4-Autopilot ### 설명 - - -### 사용법 +### Usage {#sensor_mag_sim_usage} ``` sensor_mag_sim [arguments...] @@ -885,24 +838,22 @@ Source: [modules/sensors](https://github.com/PX4/PX4-Autopilot/tree/main/src/mod The sensors module is central to the whole system. It takes low-level output from drivers, turns it into a more usable form, and publishes it for the rest of the system. -제공 기능은 다음과 같습니다: +The provided functionality includes: - Read the output from the sensor drivers (`SensorGyro`, etc.). - 동일한 유형이 여러 개 있는 경우 투표 및 장애 조치 처리를 수행합니다. - 그런 다음, 보드 회전 및 온도 보정을 적용합니다(활성화된 경우). And finally publish the data; one of the + If there are multiple of the same type, do voting and failover handling. + Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the topics is `SensorCombined`, used by many parts of the system. - Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or - on startup. 센서 드라이버는 매개변수 업데이트를 위하여 ioctl 인터페이스를 사용합니다. For this to work properly, the + on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the sensor drivers must already be running when `sensors` is started. - Do sensor consistency checks and publish the `SensorsStatusImu` topic. ### 구현 -자체 스레드에서 실행되고, 현재 선택된 자이로 주제를 폴링합니다. +It runs in its own thread and polls on the currently selected gyro topic. - - -### 사용법 +### Usage {#sensors_usage} ``` sensors [arguments...] @@ -921,9 +872,7 @@ Source: [modules/simulation/system_power_simulator](https://github.com/PX4/PX4-A ### 설명 - - -### 사용법 +### Usage {#system_power_simulation_usage} ``` system_power_simulation [arguments...] @@ -943,9 +892,7 @@ Source: [drivers/tattu_can](https://github.com/PX4/PX4-Autopilot/tree/main/src/d Driver for reading data from the Tattu 12S 16000mAh smart battery. - - -### 사용법 +### Usage {#tattu_can_usage} ``` tattu_can [arguments...] @@ -969,9 +916,7 @@ whenever a change in temperature is detected. The module can also be configured routine at next boot, which allows the thermal calibration coeffecients to be calculated while the vehicle undergoes a temperature cycle. - - -### 사용법 +### Usage {#temperature_compensation_usage} ``` temperature_compensation [arguments...] @@ -1001,9 +946,7 @@ Writes the RTC time cyclically to a file and reloads this value on startup. This allows monotonic time on systems that only have a software RTC (that is not battery powered). Explicitly setting the time backwards (e.g. via system_time) is still possible. - - -### 사용법 +### Usage {#time_persistor_usage} ``` time_persistor [arguments...] @@ -1037,9 +980,7 @@ Play system tune #2: tune_control play -t 2 ``` - - -### 사용법 +### Usage {#tune_control_usage} ``` tune_control [arguments...] @@ -1075,9 +1016,7 @@ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600 uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555 ``` - - -### 사용법 +### Usage {#uxrce_dds_client_usage} ``` uxrce_dds_client [arguments...] @@ -1108,9 +1047,7 @@ Source: [systemcmds/work_queue](https://github.com/PX4/PX4-Autopilot/tree/main/s Command-line tool to show work queue status. - - -### 사용법 +### Usage {#work_queue_usage} ``` work_queue [arguments...] diff --git a/docs/ko/modules/modules_template.md b/docs/ko/modules/modules_template.md index 3605617774..aad61d7aa0 100644 --- a/docs/ko/modules/modules_template.md +++ b/docs/ko/modules/modules_template.md @@ -16,15 +16,13 @@ Source: [templates/template_module](https://github.com/PX4/PX4-Autopilot/tree/ma ### 예 -CLI 사용 예: +CLI usage example: ``` module start -f -p 42 ``` - - -### 사용법 +### Usage {#module_usage} ``` module [arguments...] @@ -47,9 +45,7 @@ Source: [examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/ 작업 대기열에서 실행되는 간단한 모듈의 예입니다. - - -### 사용법 +### Usage {#work_item_example_usage} ``` work_item_example [arguments...] diff --git a/docs/ko/sim_sih/index.md b/docs/ko/sim_sih/index.md index e7991e0c62..254896a26f 100644 --- a/docs/ko/sim_sih/index.md +++ b/docs/ko/sim_sih/index.md @@ -58,6 +58,7 @@ To set up/start SIH: 2. Open QGroundControl and wait for the flight controller too boot and connect. 3. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame: - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) + - SIH Hexacopter X currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently. - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) @@ -116,25 +117,31 @@ To run SIH as SITL: 1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md). 2. Run the appropriate make command for each vehicle type (at the root of the PX4-Autopilot repository): - - quadrotor: + - Quadcopter ```sh make px4_sitl sihsim_quadx ``` - - Fixed-wing (plane): + - Hexacopter + + ```sh + make px4_sitl sihsim_hex + ``` + + - Fixed-wing (plane) ```sh make px4_sitl sihsim_airplane ``` - - XVert VTOL tailsitter: + - XVert VTOL tailsitter ```sh make px4_sitl sihsim_xvert ``` - - Standard VTOL: + - 표준 VTOL ```sh make px4_sitl sihsim_standard_vtol @@ -235,7 +242,8 @@ For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init. The dynamic models for the various vehicles are: -- Quadrotor: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). +- Quadcopter: [pdf report](https://github.com/PX4/PX4-user_guide/raw/main/assets/simulation/SIH_dynamic_model.pdf). +- Hexacopter: Equivalent to the Quadcopter but with a symmetric hexacopter x actuation setup. - Fixed-wing: Inspired by the PhD thesis: "Dynamics modeling of agile fixed-wing unmanned aerial vehicles." Khan, Waqas, supervised by Nahon, Meyer, McGill University, PhD thesis, 2016. - Tailsitter: Inspired by the master's thesis: "Modeling and control of a flying wing tailsitter unmanned aerial vehicle." Chiappinelli, Romain, supervised by Nahon, Meyer, McGill University, Masters thesis, 2018. diff --git a/docs/ko/simulation/community_supported_simulators.md b/docs/ko/simulation/community_supported_simulators.md index 06ae3f23a4..0cfea9b84f 100644 --- a/docs/ko/simulation/community_supported_simulators.md +++ b/docs/ko/simulation/community_supported_simulators.md @@ -12,10 +12,10 @@ See [Toolchain Installation](../dev_setup/dev_env.md) for information about the The tools have variable levels of support from their communities (some are well supported and others are not). Questions about these tools should be raised on the [discussion forums](../contribute/support.md#forums-and-chat) -| 시뮬레이터 | 설명 | -| ---------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| -| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| -| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| -| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a very significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| -| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

An alternative to HITL that offers a hard real-time simulation directly on the hardware autopilot. This simulator is implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih).

Supported Vehicles: Plane, Quad, Tailsitter, Standard VTOL

| +| 시뮬레이터 | 설명 | +| ---------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL

| +| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| +| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| +| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| +| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a very significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| From f067d7a6d86ae42a7c04ddd0e27a8d4ac1f294c8 Mon Sep 17 00:00:00 2001 From: Balduin Date: Tue, 20 May 2025 17:30:39 +0200 Subject: [PATCH 026/130] Loong: Pitch tuning --- docs/assets/airframes/vtol/foxtech_loong_2160/loong.params | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/assets/airframes/vtol/foxtech_loong_2160/loong.params b/docs/assets/airframes/vtol/foxtech_loong_2160/loong.params index cbe7060990..0f0c012b79 100644 --- a/docs/assets/airframes/vtol/foxtech_loong_2160/loong.params +++ b/docs/assets/airframes/vtol/foxtech_loong_2160/loong.params @@ -2,7 +2,7 @@ # # Stack: PX4 Pro # Vehicle: VTOL -# Version: 1.13.0 +# Version: 1.13.0 # Git Revision: 89b7373cb202071a # # Vehicle-Id Component-Id Name Value Type @@ -39,7 +39,7 @@ 1 1 FW_AIRSPD_TRIM 17.000000000000000000 9 1 1 FW_PR_FF 0.300000011920928955 9 1 1 FW_PR_I 0.500000000000000000 9 -1 1 FW_PR_P 0.400000005960464478 9 +1 1 FW_PR_P 0.3 9 1 1 FW_PSP_OFF 3.000000000000000000 9 1 1 FW_P_LIM_MAX 30.000000000000000000 9 1 1 FW_P_TC 0.349999994039535522 9 @@ -124,4 +124,4 @@ 1 1 VT_F_TR_OL_TM 9.000000000000000000 9 1 1 VT_LND_PITCH_MIN 0.000000000000000000 9 1 1 VT_PITCH_MIN 3.000000000000000000 9 -1 1 VT_TRANS_MIN_TM 5.000000000000000000 9 \ No newline at end of file +1 1 VT_TRANS_MIN_TM 5.000000000000000000 9 From 65c180852fe02aef573844d1a38c5bb905ffd8b0 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 16 May 2025 17:00:01 +0200 Subject: [PATCH 027/130] i2c_launcher: Dehardcode battery index --- src/systemcmds/i2c_launcher/i2c_launcher.cpp | 24 +++++++++++++++----- src/systemcmds/i2c_launcher/i2c_launcher.hpp | 5 ++-- 2 files changed, 21 insertions(+), 8 deletions(-) diff --git a/src/systemcmds/i2c_launcher/i2c_launcher.cpp b/src/systemcmds/i2c_launcher/i2c_launcher.cpp index db8b522132..c2a46a39f1 100644 --- a/src/systemcmds/i2c_launcher/i2c_launcher.cpp +++ b/src/systemcmds/i2c_launcher/i2c_launcher.cpp @@ -40,11 +40,17 @@ constexpr I2CLauncher::I2CDevice I2CLauncher::_devices[]; -I2CLauncher::I2CLauncher(int bus) : +I2CLauncher::I2CLauncher(int bus, int batt_index) : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(bus)), _bus(bus) { + if (_batt_index == -1) { + _batt_index = bus; + + } else { + _batt_index = batt_index; + } } I2CLauncher::~I2CLauncher() @@ -87,10 +93,10 @@ void I2CLauncher::Run() return; } - scan_i2c_bus(_bus); + scan_i2c_bus(_bus, _batt_index); } -void I2CLauncher::scan_i2c_bus(int bus) +void I2CLauncher::scan_i2c_bus(int bus, int batt_index) { struct i2c_master_s *i2c_dev = px4_i2cbus_initialize(bus); @@ -163,7 +169,7 @@ void I2CLauncher::scan_i2c_bus(int bus) if (found) { char buf[32]; - snprintf(buf, sizeof(buf), "%s -X -b %d -t %d start", _devices[i].cmd, bus, bus); + snprintf(buf, sizeof(buf), "%s -X -b %d -t %d start", _devices[i].cmd, bus, batt_index); PX4_INFO("Found address 0x%x, running '%s'\n", _devices[i].i2c_addr, buf); @@ -204,6 +210,7 @@ Daemon that starts drivers based on found I2C devices. PRINT_MODULE_USAGE_NAME("i2c_launcher", "system"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_INT('b', 0, 1, 4, "Bus number", false); + PRINT_MODULE_USAGE_PARAM_INT('t', 1, 1, 3, "battery index for calibration values (1 or 3)", false); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; @@ -215,18 +222,23 @@ extern "C" __EXPORT int i2c_launcher_main(int argc, char *argv[]) static I2CLauncher* instances[I2C_BUS_MAX_BUS_ITEMS]; int bus = -1; + int batt_index = -1; int myoptind = 1; int ch; const char *myoptarg = nullptr; const char *verb = argv[1]; - while ((ch = px4_getopt(argc, argv, "b:", &myoptind, &myoptarg)) != EOF) { + while ((ch = px4_getopt(argc, argv, "b:t:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'b': bus = strtol(myoptarg, nullptr, 10); break; + case 't': + batt_index = strtol(myoptarg, nullptr, 10); + break; + default: return ThisDriver::print_usage("unrecognized flag"); } @@ -250,7 +262,7 @@ extern "C" __EXPORT int i2c_launcher_main(int argc, char *argv[]) if (strcmp(verb, "start") == 0) { - instances[bus] = new I2CLauncher(bus); + instances[bus] = new I2CLauncher(bus, batt_index); if (instances[bus]) { diff --git a/src/systemcmds/i2c_launcher/i2c_launcher.hpp b/src/systemcmds/i2c_launcher/i2c_launcher.hpp index 18884e3ac4..0922dfb6ca 100644 --- a/src/systemcmds/i2c_launcher/i2c_launcher.hpp +++ b/src/systemcmds/i2c_launcher/i2c_launcher.hpp @@ -51,7 +51,7 @@ using namespace time_literals; class I2CLauncher : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { public: - I2CLauncher(int bus); + I2CLauncher(int bus, int batt_index); ~I2CLauncher() override; @@ -78,11 +78,12 @@ private: void Run() override; - static void scan_i2c_bus(int bus); + static void scan_i2c_bus(int bus, int batt_index); uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; // regular subscription for additional data int _bus; + int _batt_index; bool _armed {false}; }; From 31ab3f0ac9b97b6c8081d4db82183a6bf34c8051 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Thu, 22 May 2025 19:57:13 -0600 Subject: [PATCH 028/130] boards: ark_fpv add vtol att control (#24767) Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> --- boards/ark/fpv/default.px4board | 2 ++ 1 file changed, 2 insertions(+) diff --git a/boards/ark/fpv/default.px4board b/boards/ark/fpv/default.px4board index 7692aaeef3..f1f021b44e 100644 --- a/boards/ark/fpv/default.px4board +++ b/boards/ark/fpv/default.px4board @@ -56,9 +56,11 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y +CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y CONFIG_SYSTEMCMDS_BSONDUMP=y CONFIG_SYSTEMCMDS_DMESG=y From 134ee7b64085c6e8bd0bdc22f59d0e0980c1c5f8 Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Wed, 21 May 2025 18:46:22 +0200 Subject: [PATCH 029/130] dds: clean up timesync --- src/lib/timesync/Timesync.cpp | 4 +-- src/lib/timesync/Timesync.hpp | 2 +- .../uxrce_dds_client/uxrce_dds_client.cpp | 25 ++++++------------- 3 files changed, 10 insertions(+), 21 deletions(-) diff --git a/src/lib/timesync/Timesync.cpp b/src/lib/timesync/Timesync.cpp index 98b4902c23..078c60d249 100644 --- a/src/lib/timesync/Timesync.cpp +++ b/src/lib/timesync/Timesync.cpp @@ -66,7 +66,7 @@ void Timesync::update(const uint64_t now_us, const int64_t remote_timestamp_ns, // We reset the filter if we received 5 consecutive samples which violate our present estimate. // This is most likely due to a time jump on the offboard system. if (_high_deviation_count > MAX_CONSECUTIVE_HIGH_DEVIATION) { - PX4_WARN("time jump detected. Resetting time synchroniser."); + PX4_DEBUG("time jump detected. Resetting time synchroniser."); // Reset the filter reset_filter(); } @@ -104,7 +104,7 @@ void Timesync::update(const uint64_t now_us, const int64_t remote_timestamp_ns, _high_rtt_count++; if (_high_rtt_count == MAX_CONSECUTIVE_HIGH_RTT) { - PX4_WARN("RTT too high for timesync: %llu ms", rtt_us / 1000ULL); + PX4_DEBUG("RTT too high for timesync: %llu ms", rtt_us / 1000ULL); } } diff --git a/src/lib/timesync/Timesync.hpp b/src/lib/timesync/Timesync.hpp index 2948be529d..4844713442 100644 --- a/src/lib/timesync/Timesync.hpp +++ b/src/lib/timesync/Timesync.hpp @@ -78,7 +78,7 @@ static constexpr uint32_t CONVERGENCE_WINDOW = 500; // Outlier rejection and filter reset // // Samples with round-trip time higher than MAX_RTT_SAMPLE are not used to update the filter. -// More than MAX_CONSECUTIVE_HIGH_RTT number of such events in a row will throw a warning +// More than MAX_CONSECUTIVE_HIGH_RTT number of such events in a row will throw a debug message // but not reset the filter. // Samples whose calculated clock offset is more than MAX_DEVIATION_SAMPLE off from the current // estimate are not used to update the filter. More than MAX_CONSECUTIVE_HIGH_DEVIATION number diff --git a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp index 9cc9bd516b..d8beb4f609 100644 --- a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp +++ b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp @@ -54,29 +54,19 @@ static constexpr uint8_t TIMESYNC_MAX_TIMEOUTS = 10; using namespace time_literals; -static void on_time(uxrSession *session, int64_t current_time, int64_t received_timestamp, int64_t transmit_timestamp, - int64_t originate_timestamp, void *args) +static void on_time(uxrSession *session, int64_t current_time, int64_t client_transmit_timestamp, + int64_t agent_receive_timestamp, int64_t originate_timestamp, void *args) { - // latest round trip time (RTT) - int64_t rtt = current_time - originate_timestamp; - - // HRT to AGENT - int64_t offset_1 = (received_timestamp - originate_timestamp) - (rtt / 2); - int64_t offset_2 = (transmit_timestamp - current_time) - (rtt / 2); - - session->time_offset = (offset_1 + offset_2) / 2; - if (args) { Timesync *timesync = static_cast(args); - timesync->update(current_time / 1000, transmit_timestamp, originate_timestamp); + timesync->update(current_time / 1000, agent_receive_timestamp, originate_timestamp); session->time_offset = -timesync->offset() * 1000; // us -> ns } } -static void on_time_no_sync(uxrSession *session, int64_t current_time, int64_t received_timestamp, - int64_t transmit_timestamp, - int64_t originate_timestamp, void *args) +static void on_time_no_sync(uxrSession *session, int64_t current_time, int64_t client_transmit_timestamp, + int64_t agent_receive_timestamp, int64_t originate_timestamp, void *args) { session->time_offset = 0; } @@ -693,7 +683,6 @@ void UxrceddsClient::run() if (_synchronize_timestamps && hrt_elapsed_time(&last_sync_session) > 1_s) { if (uxr_sync_session(&session, 10) && _timesync.sync_converged()) { - //PX4_INFO("synchronized with time offset %-5" PRId64 "ns", session.time_offset); last_sync_session = hrt_absolute_time(); if (_param_uxrce_dds_syncc.get() > 0) { @@ -702,10 +691,10 @@ void UxrceddsClient::run() } if (!_timesync_converged && _timesync.sync_converged()) { - PX4_INFO("time sync converged"); + PX4_DEBUG("time sync converged"); } else if (_timesync_converged && !_timesync.sync_converged()) { - PX4_WARN("time sync no longer converged"); + PX4_DEBUG("time sync no longer converged"); } _timesync_converged = _timesync.sync_converged(); From b4b3c2a4a1776c22fb5ba33205a30c378ead645f Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Sat, 24 May 2025 16:03:04 +1000 Subject: [PATCH 030/130] VehicleCommand.msg - update to new docs standards (#24855) --- Tools/ci/check_msg_versioning.sh | 6 +- msg/versioned/VehicleCommand.msg | 256 +++++++++++++++---------------- 2 files changed, 131 insertions(+), 131 deletions(-) diff --git a/Tools/ci/check_msg_versioning.sh b/Tools/ci/check_msg_versioning.sh index 37c593d277..508a344ee6 100755 --- a/Tools/ci/check_msg_versioning.sh +++ b/Tools/ci/check_msg_versioning.sh @@ -27,9 +27,9 @@ do # - An old .msg version exists # - A translation header exists and is included - # Ignore changes to comments or constants - content_a=$(git show "${BASE_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v =) - content_b=$(git show "${HEAD_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v =) + # Ignore changes to comments or constants and trim whitespace + content_a=$(git show "${BASE_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v = | sed 's/^ *//;s/[ \t]*$//') + content_b=$(git show "${HEAD_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v = | sed 's/^ *//;s/[ \t]*$//') if [ "${content_a}" == "${content_b}" ]; then echo "No version update required for ${file}" continue diff --git a/msg/versioned/VehicleCommand.msg b/msg/versioned/VehicleCommand.msg index bd1e84551f..669a4b8af9 100644 --- a/msg/versioned/VehicleCommand.msg +++ b/msg/versioned/VehicleCommand.msg @@ -3,127 +3,127 @@ uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start. -uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command -uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command -uint16 VEHICLE_CMD_CUSTOM_2 = 2 # test command -uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |Unused (FW pitch from FW_TKO_PITCH_MIN)|Unused|Unused|Yaw angle in NED if yaw source available, ignored otherwise [deg] [@range 0,360]|Latitude (WGS-84)|Longitude (WGS-84)|Altitude AMSL [m]| -uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing -uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |Major Radius [m] |Minor Radius [m] |Velocity [m/s] |Orientation |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| -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_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_CONDITION_GATE = 4501 # Wait until passing a threshold |2D coord mode: 0: Orthogonal to planned route | Altitude mode: 0: Ignore altitude| Empty| Empty| Lat| Lon| Alt| -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 cycles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| 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_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value |Altitude| Frame of new altitude | Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1| Actuator 2| Actuator 3| Actuator 4| Actuator 5| Actuator 6| Index| -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 autonomous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |Ground speed [m/s] |Bitmask |Loiter radius [m] for planes |Yaw [deg] |Latitude |Longitude |Altitude | +uint16 VEHICLE_CMD_CUSTOM_0 = 0 # Test command. +uint16 VEHICLE_CMD_CUSTOM_1 = 1 # Test command. +uint16 VEHICLE_CMD_CUSTOM_2 = 2 # Test command. +uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |[s] (decimal) Hold time. (ignored by fixed wing, time to stay at MISSION for rotary wing)|[m] Acceptance radius (if the sphere with this radius is hit, the MISSION counts as reached)|0 to pass through the WP, if > 0 radius [m] to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.|Desired yaw angle at MISSION (rotary wing)|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time. |Unused|Unused|[m] Radius around MISSION. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns. |Turns|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for time. |[s] Seconds (decimal)|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand. |Unused (FW pitch from FW_TKO_PITCH_MIN)|Unused|Unused|[deg] [@range 0,360] Yaw angle in NED if yaw source available, ignored otherwise|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude AMSL| +uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing. +uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |[m] Radius|[m/s] Velocity|[@enum ORBIT_YAW_BEHAVIOUR] Yaw behaviour|Unused|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |[m] Major radius|[m] Minor radius|[m/s] Velocity|Orientation|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| +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|Unused|[deg] [@range 0, 360] Yaw angle at goal, in compass degrees|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|Unused|Unused|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. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min AMSL - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time. |[s] Delay (decimal, -1 to enable time-of-day fields)|[h] hour (24h format, UTC, -1 to ignore)|minute (24h format, UTC, -1 to ignore)|second (24h format, UTC)|Unused|Unused|Unused| +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.|Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |[s] Delay (decimal seconds)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached.|Descent / Ascend rate (m/s)|Unused|Unused|Unused|Unused|Unused|Finish Altitude| +uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance [m]|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |[deg] [@range 0,360] Target angle. 0 is north|[deg/s] Speed during yaw change|[@range -1,1] Direction: negative: counter clockwise, positive: clockwise |[ 1,0] Relative offset or absolute angle|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_GATE = 4501 # Wait until passing a threshold. |2D coord mode: 0: Orthogonal to planned route|Altitude mode: 0: Ignore altitude|Unused|Unused|Lat|Lon|Alt| +uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE|Unused|Unused|Unused|Unused|Unused|Unused| +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|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |[@enum SPEED_TYPE] Speed type (0=Airspeed, 1=Ground Speed)|Speed (m/s, -1 indicates no change)|[%] Throttle ( Percent, -1 indicates no change)|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|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|Unused|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cycles with a desired period. |Relay number|Cycle count|[s] Cycle time (decimal seconds)|Unused|Unused|Unused|Unused| +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|[us] PWM rate (1000 to 2000 typical)|Cycle count|[s] Cycle time|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately. |Flight termination activated if > 0.5|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value. |Altitude|Frame of new altitude|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1|Actuator 2|Actuator 3|Actuator 4|Actuator 5|Actuator 6|Index| +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. |Unused|Unused|Unused|Unused|Latitude|Longitude|Unused| +uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonomous landing. |[m] Altitude|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |[m/s] Ground speed|Bitmask|[m] Loiter radius for planes|[deg] Yaw|Latitude|Longitude|Altitude| uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193 -uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint| -uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| +uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Pitch offset from next waypoint|Roll offset from next waypoint|Yaw offset from next waypoint| +uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)|Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw|Transmission mode: 0: video stream, >0: single images every n seconds (decimal seconds)|Recording: 0: disabled, 1: enabled compressed, 2: enabled raw|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| uint16 VEHICLE_CMD_DO_DIGICAM_CONTROL=203 -uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # motor test command |Instance (1, ...)| throttle type| throttle| timeout [s]| Motor count | Test order| Empty| -uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # 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_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See mavlink spec MAV_CMD_PREFLIGHT_CALIBRATION -uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration -uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| -uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started -uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty| -uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode |MAV_STANDARD_MODE| -uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal +uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount. |[@enum MAV_MOUNT_MODE] Mount operation mode|Stabilize roll? (1 = yes, 0 = no)|Stabilize pitch? (1 = yes, 0 = no)|stabilize yaw? (1 = yes, 0 = no)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount. |[deg] Pitch or lat, depending on mount mode.|[deg] Roll or lon depending on mount mode|[deg]/[m] Yaw or alt depending on mount mode|Unused|Unused|Unused|[@enum MAV_MOUNT_MODE]| +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence. |enable? (0=disable, 1=enable)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute. |action [@enum PARACHUTE_ACTION] (0=disable, 1=enable, 2=release, for some systems see [@enum PARACHUTE_ACTION], not in general message set.)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # Motor test command. |Instance (@range 1, )|throttle type|throttle|timeout [s]|Motor count|Test order|Unused| +uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight. |inverted (0=normal, 1=inverted)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper. +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight. |[m] Camera trigger distance|Shutter integration time (ms)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)|q2 - quaternion param #2, x (0 in null-rotation)|q3 - quaternion param #3, y (0 in null-rotation)|q4 - quaternion param #4, z (0 in null-rotation)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min(AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See MAVLink spec MAV_CMD_PREFLIGHT_CALIBRATION. +uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# Param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration. +uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow|X axis offset (or generic dimension 1), in the sensor's raw units|Y axis offset (or generic dimension 2), in the sensor's raw units|Z axis offset (or generic dimension 3), in the sensor's raw units|Generic dimension 4, in the sensor's raw units|Generic dimension 5, in the sensor's raw units|Generic dimension 6, in the sensor's raw units| +uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started. +uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.|0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Camera minimum trigger interval|Number of positions|Roll|Pitch|Unused| +uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode. |MAV_STANDARD_MODE| +uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal. -uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| -uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command|value [-1,1]|timeout [s]|Empty|Empty|output function| -uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|configuration|Empty|Empty|Empty|output function| -uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm -uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. -uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes -uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| -uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message -uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| -uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.) -uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom +uint16 VEHICLE_CMD_MISSION_START = 300 # Start running a mission. |first_item: the first mission item to run|last_item: the last mission item to run (after this item is run, the mission ends)| +uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command. |[@range -1,1] value|[s] timeout|Unused|Unused|output function| +uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command. |configuration|Unused|Unused|Unused|output function| +uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component. |1 to arm, 0 to disarm. +uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. +uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes. +uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing. |0:Spektrum|0:Spektrum DSM2, 1:Spektrum DSMX| +uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message. +uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities|Reserved (all remaining params)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)| +uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). +uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control -uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. -uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system -uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. -uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. -uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data -uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data -uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link -uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition -uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization -uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan -uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment -uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. -uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. +uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. +uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. +uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. +uint16 VEHICLE_CMD_LOGGING_START = 2510 # Start streaming ULog data. +uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # Stop streaming ULog data. +uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # Control starting/stopping transmitting data over the high latency link. +uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition. +uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization. +uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan. +uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment. +uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. +uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. -uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # external reset of estimator global position when deadreckoning +uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # External reset of estimator global position when dead reckoning. uint16 VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE = 43004 -# PX4 vehicle commands (beyond 16 bit mavlink commands) -uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX) -uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position |Unused|Unused|Unused|Unused|Latitude (WGS-84)|Longitude (WGS-84)|Altitude [m] (AMSL from GNSS, positive above ground)| -uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty| +# PX4 vehicle commands (beyond 16 bit MAVLink commands). +uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # Start of PX4 internal only vehicle commands (> UINT16_MAX). +uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Unused|Unused|Unused|Unused|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude (AMSL from GNSS, positive above ground)| +uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Unused|Unused|Unused|Unused|Unused|Unused| -uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization | -uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | -uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt | -uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # +uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization. +uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt. +uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # -uint8 VEHICLE_ROI_NONE = 0 # No region of interest | -uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | -uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | -uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | -uint8 VEHICLE_ROI_TARGET = 4 # Point toward target +uint8 VEHICLE_ROI_NONE = 0 # No region of interest. +uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION. +uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION. +uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location. +uint8 VEHICLE_ROI_TARGET = 4 # Point toward target. uint8 VEHICLE_ROI_ENUM_END = 5 uint8 PARACHUTE_ACTION_DISABLE = 0 @@ -155,13 +155,13 @@ uint8 FAILURE_TYPE_SLOW = 5 uint8 FAILURE_TYPE_DELAYED = 6 uint8 FAILURE_TYPE_INTERMITTENT = 7 -# used as param1 in DO_CHANGE_SPEED command +# Used as param1 in DO_CHANGE_SPEED command. uint8 SPEED_TYPE_AIRSPEED = 0 uint8 SPEED_TYPE_GROUNDSPEED = 1 uint8 SPEED_TYPE_CLIMB_SPEED = 2 uint8 SPEED_TYPE_DESCEND_SPEED = 3 -# used as param3 in CMD_DO_ORBIT +# Used as param3 in CMD_DO_ORBIT. uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0 uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 @@ -169,29 +169,29 @@ uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 -# used as param1 in ARM_DISARM command +# Used as param1 in ARM_DISARM command. int8 ARMING_ACTION_DISARM = 0 int8 ARMING_ACTION_ARM = 1 -# param2 in VEHICLE_CMD_DO_GRIPPER +# param2 in VEHICLE_CMD_DO_GRIPPER. uint8 GRIPPER_ACTION_RELEASE = 0 uint8 GRIPPER_ACTION_GRAB = 1 uint8 ORB_QUEUE_LENGTH = 8 -float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. -uint32 command # Command ID -uint8 target_system # System which should execute the command -uint8 target_component # Component which should execute the command, 0 for all components -uint8 source_system # System sending the command -uint16 source_component # Component / mode executor sending the command -uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. +uint32 command # Command ID. +uint8 target_system # System which should execute the command. +uint8 target_component # Component which should execute the command, 0 for all components. +uint8 source_system # System sending the command. +uint16 source_component # Component / mode executor sending the command. +uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command). bool from_external uint16 COMPONENT_MODE_EXECUTOR_START = 1000 From 52f0ef927d3b1e1a2a7e6e15fd58d17f1de7ced1 Mon Sep 17 00:00:00 2001 From: "murata,katsutoshi" Date: Sun, 25 May 2025 06:24:13 +0900 Subject: [PATCH 031/130] dataman_client: Combine type declarations and processing (#23593) --- src/lib/dataman_client/DatamanClient.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/src/lib/dataman_client/DatamanClient.cpp b/src/lib/dataman_client/DatamanClient.cpp index c2c0ec995f..0e10b22d11 100644 --- a/src/lib/dataman_client/DatamanClient.cpp +++ b/src/lib/dataman_client/DatamanClient.cpp @@ -153,7 +153,6 @@ bool DatamanClient::readSync(dm_item_t item, uint32_t index, uint8_t *buffer, ui return false; } - bool success = false; hrt_abstime timestamp = hrt_absolute_time(); dataman_request_s request; @@ -165,7 +164,7 @@ bool DatamanClient::readSync(dm_item_t item, uint32_t index, uint8_t *buffer, ui request.item = static_cast(item); dataman_response_s response{}; - success = syncHandler(request, response, timestamp, timeout); + bool success = syncHandler(request, response, timestamp, timeout); if (success) { @@ -190,7 +189,6 @@ bool DatamanClient::writeSync(dm_item_t item, uint32_t index, uint8_t *buffer, u return false; } - bool success = false; hrt_abstime timestamp = hrt_absolute_time(); dataman_request_s request; @@ -204,7 +202,7 @@ bool DatamanClient::writeSync(dm_item_t item, uint32_t index, uint8_t *buffer, u memcpy(request.data, buffer, length); dataman_response_s response{}; - success = syncHandler(request, response, timestamp, timeout); + bool success = syncHandler(request, response, timestamp, timeout); if (success) { @@ -221,7 +219,6 @@ bool DatamanClient::writeSync(dm_item_t item, uint32_t index, uint8_t *buffer, u bool DatamanClient::clearSync(dm_item_t item, hrt_abstime timeout) { - bool success = false; hrt_abstime timestamp = hrt_absolute_time(); dataman_request_s request; @@ -231,7 +228,7 @@ bool DatamanClient::clearSync(dm_item_t item, hrt_abstime timeout) request.item = static_cast(item); dataman_response_s response{}; - success = syncHandler(request, response, timestamp, timeout); + bool success = syncHandler(request, response, timestamp, timeout); if (success) { From 779a55c6dc272cd11ad3df3f8bd20425ecef30f8 Mon Sep 17 00:00:00 2001 From: RomanBapst Date: Wed, 8 Jan 2025 15:34:43 +0300 Subject: [PATCH 032/130] FW Position Controller rework - split up old module into two, one handling setpoint generation, one control - add lateral and longitudinal control setpoints topics that can also be injected from companion computer - add configuration topics that (optionally) configure the controller with limits and momentary settings Signed-off-by: RomanBapst --- ROMFS/px4fmu_common/init.d/rc.fw_apps | 1 + ROMFS/px4fmu_common/init.d/rc.vtol_apps | 3 +- .../ctrl-zero-h7-oem-revg/default.px4board | 1 + boards/airmind/mindpx-v2/default.px4board | 1 + boards/ark/fmu-v6x/default.px4board | 1 + boards/ark/fpv/default.px4board | 1 + boards/av/x-v1/default.px4board | 1 + boards/beaglebone/blue/default.px4board | 1 + boards/cuav/7-nano/default.px4board | 1 + boards/cuav/nora/default.px4board | 1 + boards/cuav/x7pro/default.px4board | 1 + boards/cubepilot/cubeorange/default.px4board | 1 + .../cubepilot/cubeorangeplus/default.px4board | 1 + boards/cubepilot/cubeyellow/default.px4board | 1 + boards/emlid/navio2/default.px4board | 1 + boards/hkust/nxt-dual/default.px4board | 1 + boards/hkust/nxt-v1/default.px4board | 1 + boards/holybro/durandal-v1/default.px4board | 1 + boards/holybro/kakuteh7/default.px4board | 1 + boards/holybro/kakuteh7mini/default.px4board | 1 + boards/holybro/kakuteh7v2/default.px4board | 1 + boards/holybro/pix32v5/default.px4board | 1 + boards/matek/h743-mini/default.px4board | 1 + boards/matek/h743-slim/default.px4board | 1 + boards/matek/h743/default.px4board | 1 + boards/micoair/h743-aio/default.px4board | 1 + boards/micoair/h743-v2/default.px4board | 1 + boards/micoair/h743/default.px4board | 1 + boards/modalai/fc-v1/default.px4board | 1 + boards/modalai/fc-v2/default.px4board | 1 + boards/mro/ctrl-zero-classic/default.px4board | 1 + boards/mro/ctrl-zero-f7-oem/default.px4board | 1 + boards/mro/ctrl-zero-f7/default.px4board | 1 + boards/mro/ctrl-zero-h7-oem/default.px4board | 1 + boards/mro/ctrl-zero-h7/default.px4board | 1 + boards/mro/pixracerpro/default.px4board | 1 + boards/mro/x21-777/default.px4board | 1 + boards/mro/x21/default.px4board | 1 + boards/nxp/fmuk66-e/default.px4board | 1 + boards/nxp/fmuk66-v3/default.px4board | 1 + boards/nxp/mr-canhubk3/fmu.px4board | 1 + boards/nxp/mr-canhubk3/sysview.px4board | 1 + boards/nxp/mr-canhubk3/zenoh.px4board | 1 + boards/nxp/tropic-community/default.px4board | 1 + boards/px4/fmu-v2/fixedwing.px4board | 1 + boards/px4/fmu-v3/default.px4board | 1 + boards/px4/fmu-v4/default.px4board | 1 + boards/px4/fmu-v4pro/default.px4board | 1 + boards/px4/fmu-v5/default.px4board | 1 + boards/px4/fmu-v5/protected.px4board | 1 + boards/px4/fmu-v5/rover.px4board | 1 + boards/px4/fmu-v5/stackcheck.px4board | 1 + boards/px4/fmu-v5x/default.px4board | 1 + boards/px4/fmu-v5x/rover.px4board | 1 + boards/px4/fmu-v6c/default.px4board | 1 + boards/px4/fmu-v6c/rover.px4board | 1 + boards/px4/fmu-v6u/default.px4board | 1 + boards/px4/fmu-v6u/rover.px4board | 1 + boards/px4/fmu-v6x/default.px4board | 1 + boards/px4/fmu-v6x/multicopter.px4board | 1 + boards/px4/fmu-v6x/rover.px4board | 1 + boards/px4/fmu-v6xrt/default.px4board | 1 + boards/px4/fmu-v6xrt/rover.px4board | 1 + boards/px4/raspberrypi/default.px4board | 1 + boards/px4/sitl/default.px4board | 1 + boards/px4/sitl/spacecraft.px4board | 1 + boards/scumaker/pilotpi/default.px4board | 1 + boards/siyi/n7/default.px4board | 1 + .../smartap-airlink/default.px4board | 1 + boards/thepeach/k1/default.px4board | 1 + boards/thepeach/r1/default.px4board | 1 + boards/x-mav/ap-h743v2/default.px4board | 1 + boards/zeroone/x6/default.px4board | 1 + msg/CMakeLists.txt | 7 +- msg/FixedWingLateralGuidanceStatus.msg | 10 + msg/FixedWingLateralSetpoint.msg | 7 + msg/FixedWingLateralStatus.msg | 4 + msg/FixedWingLongitudinalSetpoint.msg | 9 + msg/LateralControlConfiguration.msg | 3 + msg/LongitudinalControlConfiguration.msg | 11 + msg/NpfgStatus.msg | 17 - posix-configs/SITL/init/test/test_shutdown | 3 +- posix-configs/bbblue/px4_fw.config | 1 + posix-configs/rpi/px4_fw.config | 1 + src/lib/npfg/AirspeedDirectionController.cpp | 64 + src/lib/npfg/AirspeedDirectionController.hpp | 75 + src/lib/npfg/CMakeLists.txt | 8 +- src/lib/npfg/CourseToAirspeedRefMapper.cpp | 107 + src/lib/npfg/CourseToAirspeedRefMapper.hpp | 136 ++ src/lib/npfg/DirectionalGuidance.cpp | 315 +++ .../{npfg.hpp => DirectionalGuidance.hpp} | 367 +-- src/lib/npfg/npfg.cpp | 508 ----- .../CMakeLists.txt | 15 + .../FwLateralLongitudinalControl.cpp | 841 +++++++ .../FwLateralLongitudinalControl.hpp | 260 +++ .../fw_lateral_longitudinal_control/Kconfig | 5 + .../fw_lat_long_params.c | 284 +++ src/modules/fw_pos_control/CMakeLists.txt | 2 + .../ControllerConfigurationHandler.cpp | 139 ++ .../ControllerConfigurationHandler.hpp | 113 + .../FixedwingPositionControl.cpp | 1981 +++++------------ .../FixedwingPositionControl.hpp | 319 +-- .../figure_eight/FigureEight.cpp | 86 +- .../figure_eight/FigureEight.hpp | 73 +- .../fw_path_navigation_params.c | 331 +-- src/modules/logger/logged_topics.cpp | 7 +- src/modules/zenoh/Kconfig.topics | 4 - 107 files changed, 3268 insertions(+), 2920 deletions(-) create mode 100644 msg/FixedWingLateralGuidanceStatus.msg create mode 100644 msg/FixedWingLateralSetpoint.msg create mode 100644 msg/FixedWingLateralStatus.msg create mode 100644 msg/FixedWingLongitudinalSetpoint.msg create mode 100644 msg/LateralControlConfiguration.msg create mode 100644 msg/LongitudinalControlConfiguration.msg delete mode 100644 msg/NpfgStatus.msg create mode 100644 src/lib/npfg/AirspeedDirectionController.cpp create mode 100644 src/lib/npfg/AirspeedDirectionController.hpp create mode 100644 src/lib/npfg/CourseToAirspeedRefMapper.cpp create mode 100644 src/lib/npfg/CourseToAirspeedRefMapper.hpp create mode 100644 src/lib/npfg/DirectionalGuidance.cpp rename src/lib/npfg/{npfg.hpp => DirectionalGuidance.hpp} (51%) delete mode 100644 src/lib/npfg/npfg.cpp create mode 100644 src/modules/fw_lateral_longitudinal_control/CMakeLists.txt create mode 100644 src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp create mode 100644 src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp create mode 100644 src/modules/fw_lateral_longitudinal_control/Kconfig create mode 100644 src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c create mode 100644 src/modules/fw_pos_control/ControllerConfigurationHandler.cpp create mode 100644 src/modules/fw_pos_control/ControllerConfigurationHandler.hpp diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps index 81af5e1acd..b6f05837be 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_apps +++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps @@ -16,6 +16,7 @@ control_allocator start fw_rate_control start fw_att_control start fw_pos_control start +fw_lat_lon_control start airspeed_selector start # diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_apps b/ROMFS/px4fmu_common/init.d/rc.vtol_apps index c28adef56a..9962f3c83a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_apps +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_apps @@ -27,7 +27,8 @@ fi fw_rate_control start vtol fw_att_control start vtol -fw_pos_control start vtol +fw_pos_control start +fw_lat_lon_control start vtol fw_autotune_attitude_control start vtol # Start Land Detector diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board index 549ba99b73..844782f2af 100644 --- a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board +++ b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board @@ -42,6 +42,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board index 33ad75b695..e34edeb0b7 100644 --- a/boards/airmind/mindpx-v2/default.px4board +++ b/boards/airmind/mindpx-v2/default.px4board @@ -47,6 +47,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 0ec7b49c42..6b767e4675 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -57,6 +57,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/ark/fpv/default.px4board b/boards/ark/fpv/default.px4board index f1f021b44e..ef0766f144 100644 --- a/boards/ark/fpv/default.px4board +++ b/boards/ark/fpv/default.px4board @@ -38,6 +38,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/av/x-v1/default.px4board b/boards/av/x-v1/default.px4board index 86db7c85a3..a493a5623c 100644 --- a/boards/av/x-v1/default.px4board +++ b/boards/av/x-v1/default.px4board @@ -43,6 +43,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/beaglebone/blue/default.px4board b/boards/beaglebone/blue/default.px4board index 79e0d80b92..5a2f5682aa 100644 --- a/boards/beaglebone/blue/default.px4board +++ b/boards/beaglebone/blue/default.px4board @@ -31,6 +31,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/cuav/7-nano/default.px4board b/boards/cuav/7-nano/default.px4board index f6e4511ae2..fc50c0ba7a 100644 --- a/boards/cuav/7-nano/default.px4board +++ b/boards/cuav/7-nano/default.px4board @@ -43,6 +43,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index 675ffa54cb..b06d1005b3 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -51,6 +51,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index c7c30b1a1e..5491c10fc1 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -51,6 +51,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/cubepilot/cubeorange/default.px4board b/boards/cubepilot/cubeorange/default.px4board index 9bb4f368f9..411407613a 100644 --- a/boards/cubepilot/cubeorange/default.px4board +++ b/boards/cubepilot/cubeorange/default.px4board @@ -50,6 +50,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/cubepilot/cubeorangeplus/default.px4board b/boards/cubepilot/cubeorangeplus/default.px4board index ba6ed0b34f..416ccf5483 100644 --- a/boards/cubepilot/cubeorangeplus/default.px4board +++ b/boards/cubepilot/cubeorangeplus/default.px4board @@ -51,6 +51,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/cubepilot/cubeyellow/default.px4board b/boards/cubepilot/cubeyellow/default.px4board index 62cf898af9..3717771be6 100644 --- a/boards/cubepilot/cubeyellow/default.px4board +++ b/boards/cubepilot/cubeyellow/default.px4board @@ -47,6 +47,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/emlid/navio2/default.px4board b/boards/emlid/navio2/default.px4board index 722f42b410..11a066013a 100644 --- a/boards/emlid/navio2/default.px4board +++ b/boards/emlid/navio2/default.px4board @@ -33,6 +33,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/hkust/nxt-dual/default.px4board b/boards/hkust/nxt-dual/default.px4board index 4327646414..18a7d92520 100644 --- a/boards/hkust/nxt-dual/default.px4board +++ b/boards/hkust/nxt-dual/default.px4board @@ -40,6 +40,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board index b721607758..914bfd3b3a 100644 --- a/boards/hkust/nxt-v1/default.px4board +++ b/boards/hkust/nxt-v1/default.px4board @@ -42,6 +42,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/holybro/durandal-v1/default.px4board b/boards/holybro/durandal-v1/default.px4board index ecc1bc8101..199bc05367 100644 --- a/boards/holybro/durandal-v1/default.px4board +++ b/boards/holybro/durandal-v1/default.px4board @@ -45,6 +45,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/holybro/kakuteh7/default.px4board b/boards/holybro/kakuteh7/default.px4board index f4a8e0c824..cdebf407b2 100644 --- a/boards/holybro/kakuteh7/default.px4board +++ b/boards/holybro/kakuteh7/default.px4board @@ -46,6 +46,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/holybro/kakuteh7mini/default.px4board b/boards/holybro/kakuteh7mini/default.px4board index c023eae04f..b8ca1495a2 100644 --- a/boards/holybro/kakuteh7mini/default.px4board +++ b/boards/holybro/kakuteh7mini/default.px4board @@ -46,6 +46,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/holybro/kakuteh7v2/default.px4board b/boards/holybro/kakuteh7v2/default.px4board index 0f1b80b250..8bbb8f6a7e 100644 --- a/boards/holybro/kakuteh7v2/default.px4board +++ b/boards/holybro/kakuteh7v2/default.px4board @@ -46,6 +46,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/holybro/pix32v5/default.px4board b/boards/holybro/pix32v5/default.px4board index 0093ee2dcf..94b177fb87 100644 --- a/boards/holybro/pix32v5/default.px4board +++ b/boards/holybro/pix32v5/default.px4board @@ -51,6 +51,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/matek/h743-mini/default.px4board b/boards/matek/h743-mini/default.px4board index 22efafcfdb..26238797e0 100644 --- a/boards/matek/h743-mini/default.px4board +++ b/boards/matek/h743-mini/default.px4board @@ -31,6 +31,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/matek/h743-slim/default.px4board b/boards/matek/h743-slim/default.px4board index 48e937fc43..b4fe01dbdf 100644 --- a/boards/matek/h743-slim/default.px4board +++ b/boards/matek/h743-slim/default.px4board @@ -34,6 +34,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/matek/h743/default.px4board b/boards/matek/h743/default.px4board index 71024fea5c..c530e5303d 100644 --- a/boards/matek/h743/default.px4board +++ b/boards/matek/h743/default.px4board @@ -33,6 +33,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/micoair/h743-aio/default.px4board b/boards/micoair/h743-aio/default.px4board index 2d92e89d96..7af585274e 100644 --- a/boards/micoair/h743-aio/default.px4board +++ b/boards/micoair/h743-aio/default.px4board @@ -40,6 +40,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/micoair/h743-v2/default.px4board b/boards/micoair/h743-v2/default.px4board index 74f1e2de29..518132aa8d 100644 --- a/boards/micoair/h743-v2/default.px4board +++ b/boards/micoair/h743-v2/default.px4board @@ -41,6 +41,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/micoair/h743/default.px4board b/boards/micoair/h743/default.px4board index 149bcaff21..207bb39bbb 100644 --- a/boards/micoair/h743/default.px4board +++ b/boards/micoair/h743/default.px4board @@ -39,6 +39,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/modalai/fc-v1/default.px4board b/boards/modalai/fc-v1/default.px4board index b73fdd18f8..7f60b557f2 100644 --- a/boards/modalai/fc-v1/default.px4board +++ b/boards/modalai/fc-v1/default.px4board @@ -50,6 +50,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index f95c859e8c..b97c988067 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -41,6 +41,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/ctrl-zero-classic/default.px4board b/boards/mro/ctrl-zero-classic/default.px4board index 665fbc8626..86cadee29a 100644 --- a/boards/mro/ctrl-zero-classic/default.px4board +++ b/boards/mro/ctrl-zero-classic/default.px4board @@ -47,6 +47,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/ctrl-zero-f7-oem/default.px4board b/boards/mro/ctrl-zero-f7-oem/default.px4board index 9fe340b87f..13ee784818 100644 --- a/boards/mro/ctrl-zero-f7-oem/default.px4board +++ b/boards/mro/ctrl-zero-f7-oem/default.px4board @@ -45,6 +45,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/ctrl-zero-f7/default.px4board b/boards/mro/ctrl-zero-f7/default.px4board index d09ca8a5b5..e9ad953550 100644 --- a/boards/mro/ctrl-zero-f7/default.px4board +++ b/boards/mro/ctrl-zero-f7/default.px4board @@ -45,6 +45,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/ctrl-zero-h7-oem/default.px4board b/boards/mro/ctrl-zero-h7-oem/default.px4board index ec6c59888d..643c4f1a8a 100644 --- a/boards/mro/ctrl-zero-h7-oem/default.px4board +++ b/boards/mro/ctrl-zero-h7-oem/default.px4board @@ -43,6 +43,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/ctrl-zero-h7/default.px4board b/boards/mro/ctrl-zero-h7/default.px4board index 7bb96d3aca..368709da9b 100644 --- a/boards/mro/ctrl-zero-h7/default.px4board +++ b/boards/mro/ctrl-zero-h7/default.px4board @@ -44,6 +44,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index fb49c90866..46d5ac549b 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -44,6 +44,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/x21-777/default.px4board b/boards/mro/x21-777/default.px4board index cec5dd074a..c5c5f82b98 100644 --- a/boards/mro/x21-777/default.px4board +++ b/boards/mro/x21-777/default.px4board @@ -46,6 +46,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/mro/x21/default.px4board b/boards/mro/x21/default.px4board index 8640bff623..dd3a6b85f2 100644 --- a/boards/mro/x21/default.px4board +++ b/boards/mro/x21/default.px4board @@ -47,6 +47,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/nxp/fmuk66-e/default.px4board b/boards/nxp/fmuk66-e/default.px4board index 749e62e5d5..d140a687d5 100644 --- a/boards/nxp/fmuk66-e/default.px4board +++ b/boards/nxp/fmuk66-e/default.px4board @@ -48,6 +48,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/nxp/fmuk66-v3/default.px4board b/boards/nxp/fmuk66-v3/default.px4board index 268e89c70f..40ca30a25e 100644 --- a/boards/nxp/fmuk66-v3/default.px4board +++ b/boards/nxp/fmuk66-v3/default.px4board @@ -49,6 +49,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/nxp/mr-canhubk3/fmu.px4board b/boards/nxp/mr-canhubk3/fmu.px4board index 48a7883fe2..c681da011b 100644 --- a/boards/nxp/mr-canhubk3/fmu.px4board +++ b/boards/nxp/mr-canhubk3/fmu.px4board @@ -34,6 +34,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/nxp/mr-canhubk3/sysview.px4board b/boards/nxp/mr-canhubk3/sysview.px4board index 2089b09931..cf687fcfb9 100644 --- a/boards/nxp/mr-canhubk3/sysview.px4board +++ b/boards/nxp/mr-canhubk3/sysview.px4board @@ -21,6 +21,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/nxp/mr-canhubk3/zenoh.px4board b/boards/nxp/mr-canhubk3/zenoh.px4board index fe2297a554..8d4876a99f 100644 --- a/boards/nxp/mr-canhubk3/zenoh.px4board +++ b/boards/nxp/mr-canhubk3/zenoh.px4board @@ -25,6 +25,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/nxp/tropic-community/default.px4board b/boards/nxp/tropic-community/default.px4board index c7fcb205e0..c1beb1fafd 100644 --- a/boards/nxp/tropic-community/default.px4board +++ b/boards/nxp/tropic-community/default.px4board @@ -48,6 +48,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v2/fixedwing.px4board b/boards/px4/fmu-v2/fixedwing.px4board index 0bde0c7e07..3449d56615 100644 --- a/boards/px4/fmu-v2/fixedwing.px4board +++ b/boards/px4/fmu-v2/fixedwing.px4board @@ -9,4 +9,5 @@ CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y CONFIG_MODULES_AIRSPEED_SELECTOR=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index 5dec8fda22..bd268cbe2f 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -52,6 +52,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v4/default.px4board b/boards/px4/fmu-v4/default.px4board index e7906db52c..bec469793e 100644 --- a/boards/px4/fmu-v4/default.px4board +++ b/boards/px4/fmu-v4/default.px4board @@ -53,6 +53,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v4pro/default.px4board b/boards/px4/fmu-v4pro/default.px4board index ff8455c285..d090ffb140 100644 --- a/boards/px4/fmu-v4pro/default.px4board +++ b/boards/px4/fmu-v4pro/default.px4board @@ -48,6 +48,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index 1132a48bbf..13bcff46a6 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -56,6 +56,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v5/protected.px4board b/boards/px4/fmu-v5/protected.px4board index 7ea307124c..99c5c497f6 100644 --- a/boards/px4/fmu-v5/protected.px4board +++ b/boards/px4/fmu-v5/protected.px4board @@ -18,6 +18,7 @@ CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_MODULES_TEMPERATURE_COMPENSATION=n diff --git a/boards/px4/fmu-v5/rover.px4board b/boards/px4/fmu-v5/rover.px4board index 2c9e2d20d3..5fa964bc3a 100644 --- a/boards/px4/fmu-v5/rover.px4board +++ b/boards/px4/fmu-v5/rover.px4board @@ -5,6 +5,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n diff --git a/boards/px4/fmu-v5/stackcheck.px4board b/boards/px4/fmu-v5/stackcheck.px4board index e8bcadebd7..b182a1c83a 100644 --- a/boards/px4/fmu-v5/stackcheck.px4board +++ b/boards/px4/fmu-v5/stackcheck.px4board @@ -30,6 +30,7 @@ CONFIG_MODULES_EVENTS=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_GIMBAL=n CONFIG_MODULES_GYRO_CALIBRATION=n diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 8ba41726c0..9115b13ad7 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -60,6 +60,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v5x/rover.px4board b/boards/px4/fmu-v5x/rover.px4board index 42f8ec21ce..2490c28c6b 100644 --- a/boards/px4/fmu-v5x/rover.px4board +++ b/boards/px4/fmu-v5x/rover.px4board @@ -4,6 +4,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n diff --git a/boards/px4/fmu-v6c/default.px4board b/boards/px4/fmu-v6c/default.px4board index e6b812fffd..e32ec2e54b 100644 --- a/boards/px4/fmu-v6c/default.px4board +++ b/boards/px4/fmu-v6c/default.px4board @@ -48,6 +48,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v6c/rover.px4board b/boards/px4/fmu-v6c/rover.px4board index 9eed13c665..ee7cddbe05 100644 --- a/boards/px4/fmu-v6c/rover.px4board +++ b/boards/px4/fmu-v6c/rover.px4board @@ -3,6 +3,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n diff --git a/boards/px4/fmu-v6u/default.px4board b/boards/px4/fmu-v6u/default.px4board index be90aca727..55d857d697 100644 --- a/boards/px4/fmu-v6u/default.px4board +++ b/boards/px4/fmu-v6u/default.px4board @@ -48,6 +48,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v6u/rover.px4board b/boards/px4/fmu-v6u/rover.px4board index 9eed13c665..ee7cddbe05 100644 --- a/boards/px4/fmu-v6u/rover.px4board +++ b/boards/px4/fmu-v6u/rover.px4board @@ -3,6 +3,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index ba42e02a9d..901318cf30 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -58,6 +58,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v6x/multicopter.px4board b/boards/px4/fmu-v6x/multicopter.px4board index 9f540f567d..b501d6fe4a 100644 --- a/boards/px4/fmu-v6x/multicopter.px4board +++ b/boards/px4/fmu-v6x/multicopter.px4board @@ -4,6 +4,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_COMMON_RC=y diff --git a/boards/px4/fmu-v6x/rover.px4board b/boards/px4/fmu-v6x/rover.px4board index 9eed13c665..ee7cddbe05 100644 --- a/boards/px4/fmu-v6x/rover.px4board +++ b/boards/px4/fmu-v6x/rover.px4board @@ -3,6 +3,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 477ba76ed8..6710e97b6a 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -58,6 +58,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/fmu-v6xrt/rover.px4board b/boards/px4/fmu-v6xrt/rover.px4board index 7b8ed3bd1f..f7af280b03 100644 --- a/boards/px4/fmu-v6xrt/rover.px4board +++ b/boards/px4/fmu-v6xrt/rover.px4board @@ -4,6 +4,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n diff --git a/boards/px4/raspberrypi/default.px4board b/boards/px4/raspberrypi/default.px4board index ade7dd4235..c8034269aa 100644 --- a/boards/px4/raspberrypi/default.px4board +++ b/boards/px4/raspberrypi/default.px4board @@ -31,6 +31,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index f85c03e23a..7da14ff720 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -20,6 +20,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_FIGURE_OF_EIGHT=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/sitl/spacecraft.px4board b/boards/px4/sitl/spacecraft.px4board index 56c966598b..121c7ca9f7 100644 --- a/boards/px4/sitl/spacecraft.px4board +++ b/boards/px4/sitl/spacecraft.px4board @@ -3,6 +3,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_MC_ATT_CONTROL=n diff --git a/boards/scumaker/pilotpi/default.px4board b/boards/scumaker/pilotpi/default.px4board index b72da494da..8e18d35c46 100644 --- a/boards/scumaker/pilotpi/default.px4board +++ b/boards/scumaker/pilotpi/default.px4board @@ -33,6 +33,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/siyi/n7/default.px4board b/boards/siyi/n7/default.px4board index 2a7a232581..a532e87e99 100644 --- a/boards/siyi/n7/default.px4board +++ b/boards/siyi/n7/default.px4board @@ -39,6 +39,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index fdfdcdea6a..7b2a0d7a90 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -47,6 +47,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/thepeach/k1/default.px4board b/boards/thepeach/k1/default.px4board index d760279546..448268f416 100644 --- a/boards/thepeach/k1/default.px4board +++ b/boards/thepeach/k1/default.px4board @@ -45,6 +45,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/thepeach/r1/default.px4board b/boards/thepeach/r1/default.px4board index d760279546..448268f416 100644 --- a/boards/thepeach/r1/default.px4board +++ b/boards/thepeach/r1/default.px4board @@ -45,6 +45,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/x-mav/ap-h743v2/default.px4board b/boards/x-mav/ap-h743v2/default.px4board index 09a32b78c5..ccb5fe5396 100644 --- a/boards/x-mav/ap-h743v2/default.px4board +++ b/boards/x-mav/ap-h743v2/default.px4board @@ -41,6 +41,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/zeroone/x6/default.px4board b/boards/zeroone/x6/default.px4board index ba05f4ab5f..85b3a9e993 100644 --- a/boards/zeroone/x6/default.px4board +++ b/boards/zeroone/x6/default.px4board @@ -48,6 +48,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 6c374f2c35..e3008ae917 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -90,6 +90,10 @@ set(msg_files FollowTargetEstimator.msg FollowTargetStatus.msg FuelTankStatus.msg + FixedWingLateralSetpoint.msg + FixedWingLongitudinalSetpoint.msg + FixedWingLateralGuidanceStatus.msg + FixedWingLateralStatus.msg GeneratorStatus.msg GeofenceResult.msg GeofenceStatus.msg @@ -120,10 +124,12 @@ set(msg_files LandingGearWheel.msg LandingTargetInnovations.msg LandingTargetPose.msg + LateralControlConfiguration.msg LaunchDetectionStatus.msg LedControl.msg LoggerStatus.msg LogMessage.msg + LongitudinalControlConfiguration.msg MagnetometerBiasEstimate.msg MagWorkerData.msg ManualControlSwitches.msg @@ -137,7 +143,6 @@ set(msg_files NavigatorMissionItem.msg NavigatorStatus.msg NormalizedUnsignedSetpoint.msg - NpfgStatus.msg ObstacleDistance.msg OffboardControlMode.msg OnboardComputerStatus.msg diff --git a/msg/FixedWingLateralGuidanceStatus.msg b/msg/FixedWingLateralGuidanceStatus.msg new file mode 100644 index 0000000000..6295f8948e --- /dev/null +++ b/msg/FixedWingLateralGuidanceStatus.msg @@ -0,0 +1,10 @@ +uint64 timestamp # time since system start (microseconds) + +float32 course_setpoint # bearing angle (same as course) [rad] +float32 lateral_acceleration_ff # lateral acceleration demand only for maintaining curvature [m/s^2] +float32 bearing_feas # bearing feasibility [0,1] +float32 bearing_feas_on_track # on-track bearing feasibility [0,1] +float32 signed_track_error # signed track error [m] +float32 track_error_bound # track error bound [m] +float32 adapted_period # adapted period (if auto-tuning enabled) [s] +uint8 wind_est_valid # (boolean) true = wind estimate is valid and/or being used by controller (also indicates if wind est usage is disabled despite being valid) diff --git a/msg/FixedWingLateralSetpoint.msg b/msg/FixedWingLateralSetpoint.msg new file mode 100644 index 0000000000..d899993ad5 --- /dev/null +++ b/msg/FixedWingLateralSetpoint.msg @@ -0,0 +1,7 @@ +uint64 timestamp + +# NOTE: At least one of course, airspeed_direction, or lateral_acceleration must be finite + +float32 course # [-pi, pi] Course over ground setpoint, w.r.t. North. NAN if not controlled directly. +float32 airspeed_direction # [-pi, pi] Angle projected to ground of desired airspeed vector, w.r.t. North. NAN if not controlled directly, used as feedforward if course setpoint is finite. +float32 lateral_acceleration # [m/s^2] Lateral acceleration setpoint in FRD frame. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. diff --git a/msg/FixedWingLateralStatus.msg b/msg/FixedWingLateralStatus.msg new file mode 100644 index 0000000000..b877948b24 --- /dev/null +++ b/msg/FixedWingLateralStatus.msg @@ -0,0 +1,4 @@ +uint64 timestamp # time since system start (microseconds) + +float32 lateral_acceleration # resultant lateral acceleration reference [m/s^2] +float32 can_run_factor # estimate of certainty of the correct functionality of the npfg roll setpoint in [0, 1] diff --git a/msg/FixedWingLongitudinalSetpoint.msg b/msg/FixedWingLongitudinalSetpoint.msg new file mode 100644 index 0000000000..25595f76c4 --- /dev/null +++ b/msg/FixedWingLongitudinalSetpoint.msg @@ -0,0 +1,9 @@ +uint64 timestamp + +# Note: If not both pitch_direct and throttle_direct are finite, then either altitude or height_rate must be finite + +float32 altitude # [m] Altitude setpoint AMSL, NAN if not controlled +float32 height_rate # [m/s] NAN if not controlled directly, used as feedforward if altitude is finite +float32 equivalent_airspeed # [m/s] NAN if system default should be used +float32 pitch_direct # [rad] NAN if not controlled, overrides total energy controller +float32 throttle_direct # [0,1] NAN if not controlled, overrides total energy controller diff --git a/msg/LateralControlConfiguration.msg b/msg/LateralControlConfiguration.msg new file mode 100644 index 0000000000..ee96028776 --- /dev/null +++ b/msg/LateralControlConfiguration.msg @@ -0,0 +1,3 @@ +uint64 timestamp + +float32 lateral_accel_max # [m/s^2] maps 1:1 to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY diff --git a/msg/LongitudinalControlConfiguration.msg b/msg/LongitudinalControlConfiguration.msg new file mode 100644 index 0000000000..0f944cc9bf --- /dev/null +++ b/msg/LongitudinalControlConfiguration.msg @@ -0,0 +1,11 @@ +uint64 timestamp + +float32 pitch_min # [rad] +float32 pitch_max # [rad] +float32 throttle_min # [0,1] +float32 throttle_max # [0,1] +float32 climb_rate_target # [m/s] target climbrate used to change altitude +float32 sink_rate_target # [m/s] target sinkrate used to change altitude +float32 speed_weight # [0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only +bool enforce_low_height_condition # if true, total energy controller will use lower altitude control time constant +bool disable_underspeed_protection # if true, underspeed handling is disabled in the total energy controller diff --git a/msg/NpfgStatus.msg b/msg/NpfgStatus.msg deleted file mode 100644 index 132c1f7f3f..0000000000 --- a/msg/NpfgStatus.msg +++ /dev/null @@ -1,17 +0,0 @@ -uint64 timestamp # time since system start (microseconds) - -uint8 wind_est_valid # (boolean) true = wind estimate is valid and/or being used by controller (also indicates if wind est usage is disabled despite being valid) -float32 lat_accel # resultant lateral acceleration reference [m/s^2] -float32 lat_accel_ff # lateral acceleration demand only for maintaining curvature [m/s^2] -float32 bearing_feas # bearing feasibility [0,1] -float32 bearing_feas_on_track # on-track bearing feasibility [0,1] -float32 signed_track_error # signed track error [m] -float32 track_error_bound # track error bound [m] -float32 airspeed_ref # (true) airspeed reference [m/s] -float32 bearing # bearing angle [rad] -float32 heading_ref # heading angle reference [rad] -float32 min_ground_speed_ref # minimum forward ground speed reference [m/s] -float32 adapted_period # adapted period (if auto-tuning enabled) [s] -float32 p_gain # controller proportional gain [rad/s] -float32 time_const # controller time constant [s] -float32 can_run_factor # estimate of certainty of the correct functionality of the npfg roll setpoint in [0, 1] diff --git a/posix-configs/SITL/init/test/test_shutdown b/posix-configs/SITL/init/test/test_shutdown index b452595732..c61c43c0e2 100644 --- a/posix-configs/SITL/init/test/test_shutdown +++ b/posix-configs/SITL/init/test/test_shutdown @@ -29,7 +29,8 @@ flight_mode_manager start mc_pos_control start vtol mc_att_control start vtol mc_rate_control start vtol -fw_pos_control start vtol +fw_pos_control start +fw_lat_lon_control start fw_att_control start vtol airspeed_selector start diff --git a/posix-configs/bbblue/px4_fw.config b/posix-configs/bbblue/px4_fw.config index d6ba875fde..cf8bd9fef6 100644 --- a/posix-configs/bbblue/px4_fw.config +++ b/posix-configs/bbblue/px4_fw.config @@ -57,6 +57,7 @@ land_detector start fixedwing fw_att_control start fw_pos_control start +fw_lat_lon_control start mavlink start -n SoftAp -x -u 14556 -r 1000000 -p # -n name of wifi interface: SoftAp, wlan or your custom interface, diff --git a/posix-configs/rpi/px4_fw.config b/posix-configs/rpi/px4_fw.config index 55d8d9cfd9..74f59a3eb1 100644 --- a/posix-configs/rpi/px4_fw.config +++ b/posix-configs/rpi/px4_fw.config @@ -42,6 +42,7 @@ ekf2 start land_detector start fixedwing fw_att_control start fw_pos_control start +fw_lat_lon_control start mavlink start -x -u 14556 -r 1000000 -p diff --git a/src/lib/npfg/AirspeedDirectionController.cpp b/src/lib/npfg/AirspeedDirectionController.cpp new file mode 100644 index 0000000000..621587f47e --- /dev/null +++ b/src/lib/npfg/AirspeedDirectionController.cpp @@ -0,0 +1,64 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "AirspeedDirectionController.hpp" +#include +#include + +using matrix::Vector2f; +AirspeedDirectionController::AirspeedDirectionController() +{ + // Constructor +} + +float AirspeedDirectionController::controlHeading(const float heading_sp, const float heading, + const float airspeed) const +{ + + const Vector2f airspeed_vector = Vector2f{cosf(heading), sinf(heading)} * airspeed; + const Vector2f airspeed_sp_vector_unit = Vector2f{cosf(heading_sp), sinf(heading_sp)}; + + const float dot_air_vel_err = airspeed_vector.dot(airspeed_sp_vector_unit); + const float cross_air_vel_err = airspeed_vector.cross(airspeed_sp_vector_unit); + + if (dot_air_vel_err < 0.0f) { + // hold max lateral acceleration command above 90 deg heading error + return p_gain_ * ((cross_air_vel_err < 0.0f) ? -airspeed : airspeed); + + } else { + // airspeed/airspeed_ref is used to scale any incremented airspeed reference back to the current airspeed + // for acceleration commands in a "feedback" sense (i.e. at the current vehicle airspeed) + // todo use airspeed_ref or adapt comment + return p_gain_ * cross_air_vel_err; + } +} diff --git a/src/lib/npfg/AirspeedDirectionController.hpp b/src/lib/npfg/AirspeedDirectionController.hpp new file mode 100644 index 0000000000..d0111729ca --- /dev/null +++ b/src/lib/npfg/AirspeedDirectionController.hpp @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file AirspeedDirectionController.hpp + * + * Original Author: Thomas Stastny + * Refactored to better suite new control API: Roman Bapst + * + * * Notes: + * - The wind estimate should be dynamic enough to capture ~1-2 second length gusts, + * Otherwise the performance will suffer. + * + * Acknowledgements and References: + * + * The logic is mostly based on [1] and Paper III of [2]. + * TODO: Concise, up to date documentation and stability analysis for the following + * implementation. + * + * [1] T. Stastny and R. Siegwart. "On Flying Backwards: Preventing Run-away of + * Small, Low-speed, Fixed-wing UAVs in Strong Winds". IEEE International Conference + * on Intelligent Robots and Systems (IROS). 2019. + * https://arxiv.org/pdf/1908.01381.pdf + * [2] T. Stastny. "Low-Altitude Control and Local Re-Planning Strategies for Small + * Fixed-Wing UAVs". Doctoral Thesis, ETH Zürich. 2020. + * https://tstastny.github.io/pdf/tstastny_phd_thesis_wcover.pdf + */ + +#ifndef PX4_AIRSPEEDDIRECTIONONTROLLER_HPP +#define PX4_AIRSPEEDDIRECTIONONTROLLER_HPP + +class AirspeedDirectionController +{ +public: + + AirspeedDirectionController(); + + + float controlHeading(const float heading_sp, const float heading, const float airspeed) const; + +private: + float p_gain_{0.8885f}; // proportional gain (computed from period_ and damping_) [rad/s] +}; + +#endif //PX4_AIRSPEEDDIRECTIONONTROLLER_HPP diff --git a/src/lib/npfg/CMakeLists.txt b/src/lib/npfg/CMakeLists.txt index 739e6af155..d5da8fb2f2 100644 --- a/src/lib/npfg/CMakeLists.txt +++ b/src/lib/npfg/CMakeLists.txt @@ -32,8 +32,12 @@ ############################################################################ px4_add_library(npfg - npfg.cpp - npfg.hpp + DirectionalGuidance.cpp + CourseToAirspeedRefMapper.cpp + AirspeedDirectionController.cpp + DirectionalGuidance.hpp + CourseToAirspeedRefMapper.hpp + AirspeedDirectionController.hpp ) target_link_libraries(npfg PRIVATE geo) diff --git a/src/lib/npfg/CourseToAirspeedRefMapper.cpp b/src/lib/npfg/CourseToAirspeedRefMapper.cpp new file mode 100644 index 0000000000..7e745486b4 --- /dev/null +++ b/src/lib/npfg/CourseToAirspeedRefMapper.cpp @@ -0,0 +1,107 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "CourseToAirspeedRefMapper.hpp" +using matrix::Vector2f; + +float +CourseToAirspeedRefMapper::mapCourseSetpointToHeadingSetpoint(const float bearing_setpoint, const Vector2f &wind_vel, + float airspeed_sp) const +{ + const Vector2f bearing_vector = Vector2f{cosf(bearing_setpoint), sinf(bearing_setpoint)}; + const float wind_cross_bearing = wind_vel.cross(bearing_vector); + + const float airsp_dot_bearing = projectAirspOnBearing(airspeed_sp, wind_cross_bearing); + const Vector2f air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vector); + + // TODO check if we need to use infeasibleAirVelRef or other mitigation functions in some cases (high wind) + + return atan2f(air_vel_ref(1), air_vel_ref(0)); +} + +float +CourseToAirspeedRefMapper::getMinAirspeedForCurrentBearing(const float bearing_setpoint, const Vector2f &wind_vel, + float airspeed_max, float min_ground_speed) const +{ + const Vector2f bearing_vector = Vector2f{cosf(bearing_setpoint), sinf(bearing_setpoint)}; + const float wind_cross_bearing = wind_vel.cross(bearing_vector); + const float wind_dot_bearing = wind_vel.dot(bearing_vector); + + const bool wind_along_bearing_is_below_min_ground_speed = min_ground_speed > wind_dot_bearing; + + float airspeed_min = 0.f; // return 0 if no min airspeed is necessary + + if (wind_along_bearing_is_below_min_ground_speed) { + // airspeed required to achieve minimum ground speed along bearing vector (5.18) + airspeed_min = sqrtf((min_ground_speed - wind_dot_bearing) * (min_ground_speed - wind_dot_bearing) + + wind_cross_bearing * wind_cross_bearing); + + } + + return math::min(airspeed_min, airspeed_max); +} + +float CourseToAirspeedRefMapper::projectAirspOnBearing(const float airspeed_true, const float wind_cross_bearing) const +{ + // NOTE: wind_cross_bearing must be less than airspeed to use this function + // it is assumed that bearing feasibility is checked and found feasible (e.g. bearingIsFeasible() = true) prior to entering this method + // otherwise the return will be erroneous + + // 3.5.8 + return sqrtf(math::max(airspeed_true * airspeed_true - wind_cross_bearing * wind_cross_bearing, 0.0f)); +} + +int CourseToAirspeedRefMapper::bearingIsFeasible(const float wind_cross_bearing, const float wind_dot_bearing, + const float airspeed, const float wind_speed) const +{ + return (fabsf(wind_cross_bearing) < airspeed) && ((wind_dot_bearing > 0.0f) || (wind_speed < airspeed)); +} + +matrix::Vector2f +CourseToAirspeedRefMapper::solveWindTriangle(const float wind_cross_bearing, const float airsp_dot_bearing, + const Vector2f &bearing_vec) const +{ + // essentially a 2D rotation with the speeds (magnitudes) baked in + return Vector2f{airsp_dot_bearing * bearing_vec(0) - wind_cross_bearing * bearing_vec(1), + wind_cross_bearing * bearing_vec(0) + airsp_dot_bearing * bearing_vec(1)}; +} + +// matrix::Vector2f CourseToAirspeedRefMapper::infeasibleAirVelRef(const Vector2f &wind_vel, const Vector2f &bearing_vec, +// const float wind_speed, const float airspeed) const +// { +// // NOTE: wind speed must be greater than airspeed, and airspeed must be greater than zero to use this function +// // it is assumed that bearing feasibility is checked and found infeasible (e.g. bearingIsFeasible() = false) prior to entering this method +// // otherwise the normalization of the air velocity vector could have a division by zero +// Vector2f air_vel_ref = sqrtf(math::max(wind_speed * wind_speed - airspeed * airspeed, 0.0f)) * bearing_vec - wind_vel; +// return air_vel_ref.normalized() * airspeed; +// } diff --git a/src/lib/npfg/CourseToAirspeedRefMapper.hpp b/src/lib/npfg/CourseToAirspeedRefMapper.hpp new file mode 100644 index 0000000000..70f3312e9b --- /dev/null +++ b/src/lib/npfg/CourseToAirspeedRefMapper.hpp @@ -0,0 +1,136 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file CourseToAirspeedRefMapper.hpp + * + * Original Author: Thomas Stastny + * Refactored to better suite new control API: Roman Bapst + * + * * Notes: + * - The wind estimate should be dynamic enough to capture ~1-2 second length gusts, + * Otherwise the performance will suffer. + * + * Acknowledgements and References: + * + * The logic is mostly based on [1] and Paper III of [2]. + * TODO: Concise, up to date documentation and stability analysis for the following + * implementation. + * + * [1] T. Stastny and R. Siegwart. "On Flying Backwards: Preventing Run-away of + * Small, Low-speed, Fixed-wing UAVs in Strong Winds". IEEE International Conference + * on Intelligent Robots and Systems (IROS). 2019. + * https://arxiv.org/pdf/1908.01381.pdf + * [2] T. Stastny. "Low-Altitude Control and Local Re-Planning Strategies for Small + * Fixed-Wing UAVs". Doctoral Thesis, ETH Zürich. 2020. + * https://tstastny.github.io/pdf/tstastny_phd_thesis_wcover.pdf + */ + +#ifndef PX4_COURSETOAIRSPEEDREFMAPPER_HPP +#define PX4_COURSETOAIRSPEEDREFMAPPER_HPP + + +#include +#include + +class CourseToAirspeedRefMapper +{ +public: + + CourseToAirspeedRefMapper() {}; + + ~CourseToAirspeedRefMapper() = default; + + float mapCourseSetpointToHeadingSetpoint(const float bearing_setpoint, + const matrix::Vector2f &wind_vel, float airspeed_sp) const; + float getMinAirspeedForCurrentBearing(const float bearing_setpoint, + const matrix::Vector2f &wind_vel, float max_airspeed, float min_ground_speed) const; + +private: + /* + * Determines a reference air velocity *without curvature compensation, but + * including "optimal" true airspeed reference compensation in excess wind conditions. + * Nominal and maximum true airspeed member variables must be set before using this method. + * + * @param[in] wind_vel Wind velocity vector [m/s] + * @param[in] bearing_setpoint Bearing + * @param[in] airspeed_true True airspeed setpoint[m/s] + * @return Air velocity vector [m/s] + */ + matrix::Vector2f refAirVelocity(const matrix::Vector2f &wind_vel, const float bearing_setpoint, + float airspeed_true, float min_ground_speed) const; + /* + * Projection of the air velocity vector onto the bearing line considering + * a connected wind triangle. + * + * @param[in] airspeed Vehicle true airspeed setpoint [m/s] + * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] + * @return Projection of air velocity vector on bearing vector [m/s] + */ + float projectAirspOnBearing(const float airspeed, const float wind_cross_bearing) const; + /* + * Check for binary bearing feasibility. + * + * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] + * @param[in] wind_dot_bearing 2D dot product of wind velocity and bearing vector [m/s] + * @param[in] airspeed Vehicle true airspeed [m/s] + * @param[in] wind_speed Wind speed [m/s] + * @return Binary bearing feasibility: 1 if feasible, 0 if infeasible + */ + int bearingIsFeasible(const float wind_cross_bearing, const float wind_dot_bearing, const float airspeed, + const float wind_speed) const; + /* + * Air velocity solution for a given wind velocity and bearing vector assuming + * a "high speed" (not backwards) solution in the excess wind case. + * + * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] + * @param[in] airsp_dot_bearing 2D dot product of air velocity (solution) and bearing vector [m/s] + * @param[in] bearing_vec Bearing vector + * @return Air velocity reference vector [m/s] + */ + matrix::Vector2f solveWindTriangle(const float wind_cross_bearing, const float airsp_dot_bearing, + const matrix::Vector2f &bearing_vec) const; + /* + * Air velocity solution for an infeasible bearing. + * + * @param[in] wind_vel Wind velocity vector [m/s] + * @param[in] bearing_vec Bearing vector + * @param[in] wind_speed Wind speed [m/s] + * @param[in] airspeed Vehicle true airspeed [m/s] + * @return Air velocity vector [m/s] + */ + matrix::Vector2f infeasibleAirVelRef(const matrix::Vector2f &wind_vel, const matrix::Vector2f &bearing_vec, + const float wind_speed, const float airspeed) const; +}; + +#endif //PX4_COURSETOAIRSPEEDREFMAPPER_HPP diff --git a/src/lib/npfg/DirectionalGuidance.cpp b/src/lib/npfg/DirectionalGuidance.cpp new file mode 100644 index 0000000000..cd1f7aef93 --- /dev/null +++ b/src/lib/npfg/DirectionalGuidance.cpp @@ -0,0 +1,315 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file DirectionalGuidance.cpp + */ +#include "DirectionalGuidance.hpp" +using matrix::Vector2d; +using matrix::Vector2f; + +DirectionalGuidance::DirectionalGuidance() +{ + +} + +DirectionalGuidanceOutput +DirectionalGuidance::guideToPath(const Vector2f &curr_pos_local, const Vector2f &ground_vel, const Vector2f &wind_vel, + const Vector2f &unit_path_tangent, const Vector2f &position_on_path, + const float path_curvature) +{ + const float ground_speed = ground_vel.norm(); + + const Vector2f air_vel = ground_vel - wind_vel; + const float airspeed = air_vel.norm(); + + const float wind_speed = wind_vel.norm(); + + const Vector2f path_pos_to_vehicle{curr_pos_local - position_on_path}; + signed_track_error_ = unit_path_tangent.cross(path_pos_to_vehicle); + + // on-track wind triangle projections + const float wind_cross_upt = wind_vel.cross(unit_path_tangent); + const float wind_dot_upt = wind_vel.dot(unit_path_tangent); + + // calculate the bearing feasibility on the track at the current closest point + feas_on_track_ = bearingFeasibility(wind_cross_upt, wind_dot_upt, airspeed, wind_speed); + + const float track_error = fabsf(signed_track_error_); + + // update control parameters considering upper and lower stability bounds (if enabled) + // must be called before trackErrorBound() as it updates time_const_ + adapted_period_ = adaptPeriod(ground_speed, airspeed, wind_speed, track_error, + path_curvature, wind_vel, unit_path_tangent, feas_on_track_); + const float time_const = timeConst(adapted_period_, damping_); + + // track error bound is dynamic depending on ground speed + track_error_bound_ = trackErrorBound(ground_speed, time_const); + const float normalized_track_error = normalizedTrackError(track_error, track_error_bound_); + + // look ahead angle based solely on track proximity + const float look_ahead_ang = lookAheadAngle(normalized_track_error); + + track_proximity_ = trackProximity(look_ahead_ang); + + bearing_vec_ = bearingVec(unit_path_tangent, look_ahead_ang, signed_track_error_); + + // wind triangle projections + const float wind_cross_bearing = wind_vel.cross(bearing_vec_); + const float wind_dot_bearing = wind_vel.dot(bearing_vec_); + + // continuous representation of the bearing feasibility + feas_ = bearingFeasibility(wind_cross_bearing, wind_dot_bearing, airspeed, wind_speed); + + // we consider feasibility of both the current bearing as well as that on the track at the current closest point + const float feas_combined = feas_ * feas_on_track_; + // lateral acceleration needed to stay on curved track (assuming no heading error) + lateral_accel_ff_ = lateralAccelFF(unit_path_tangent, ground_vel, wind_dot_upt, + wind_cross_upt, airspeed, wind_speed, signed_track_error_, path_curvature) * feas_combined * track_proximity_; + course_sp_ = atan2f(bearing_vec_(1), bearing_vec_(0)); + + return DirectionalGuidanceOutput{.course_setpoint = course_sp_, + .lateral_acceleration_feedforward = lateral_accel_ff_}; +} + +float DirectionalGuidance::adaptPeriod(const float ground_speed, const float airspeed, const float wind_speed, + const float track_error, const float path_curvature, const Vector2f &wind_vel, + const Vector2f &unit_path_tangent, const float feas_on_track) const +{ + float period = period_; + const float air_turn_rate = fabsf(path_curvature * airspeed); + const float wind_factor = windFactor(airspeed, wind_speed); + + if (en_period_lb_ && roll_time_const_ > NPFG_EPSILON) { + // lower bound for period not considering path curvature + const float period_lb_zero_curvature = periodLowerBound(0.0f, wind_factor, feas_on_track) * period_safety_factor_; + + // lower bound for period *considering path curvature + float period_lb = periodLowerBound(air_turn_rate, wind_factor, feas_on_track) * period_safety_factor_; + + // calculate the time constant and track error bound considering the zero + // curvature, lower-bounded period and subsequently recalculate the normalized + // track error + const float time_const = timeConst(period_lb_zero_curvature, damping_); + const float track_error_bound = trackErrorBound(ground_speed, time_const); + const float normalized_track_error = normalizedTrackError(track_error, track_error_bound); + + // calculate nominal track proximity with lower bounded time constant + // (only a numerical solution can find corresponding track proximity + // and adapted gains simultaneously) + const float look_ahead_ang = lookAheadAngle(normalized_track_error); + const float track_proximity = trackProximity(look_ahead_ang); + + // linearly ramp in curvature dependent lower bound with track proximity + period_lb = period_lb * track_proximity + (1.0f - track_proximity) * period_lb_zero_curvature; + + // lower bounded period + period = math::max(period_lb, period); + + // only allow upper bounding ONLY if lower bounding is enabled (is otherwise + // dangerous to allow period decrements without stability checks). + // NOTE: if the roll time constant is not accurately known, lower-bound + // checks may be too optimistic and reducing the period can still destabilize + // the system! enable this feature at your own risk. + if (en_period_ub_) { + + const float period_ub = periodUpperBound(air_turn_rate, wind_factor, feas_on_track); + + if (en_period_ub_ && PX4_ISFINITE(period_ub) && period > period_ub) { + // NOTE: if the roll time constant is not accurately known, reducing + // the period here can destabilize the system! + // enable this feature at your own risk! + + // upper bound the period (for track keeping stability), prefer lower bound if violated + const float period_adapted = math::max(period_lb, period_ub); + + // transition from the nominal period to the adapted period as we get + // closer to the track + period = period_adapted * track_proximity + (1.0f - track_proximity) * period; + } + } + } + + return period; +} + +float DirectionalGuidance::normalizedTrackError(const float track_error, const float track_error_bound) const +{ + return math::constrain(track_error / track_error_bound, 0.0f, 1.0f); +} + +float DirectionalGuidance::windFactor(const float airspeed, const float wind_speed) const +{ + // See [TODO: include citation] for definition/elaboration of this approximation. + if (wind_speed > airspeed || airspeed < NPFG_EPSILON) { + return 2.0f; + + } else { + return 2.0f * (1.0f - sqrtf(1.0f - math::min(1.0f, wind_speed / airspeed))); + } +} + +float DirectionalGuidance::periodUpperBound(const float air_turn_rate, const float wind_factor, + const float feas_on_track) const +{ + if (air_turn_rate * wind_factor > NPFG_EPSILON) { + // multiply air turn rate by feasibility on track to zero out when we anyway + // should not consider the curvature + return 4.0f * M_PI_F * damping_ / (air_turn_rate * wind_factor * feas_on_track); + } + + return INFINITY; +} + +float DirectionalGuidance::periodLowerBound(const float air_turn_rate, const float wind_factor, + const float feas_on_track) const +{ + // this method considers a "conservative" lower period bound, i.e. a constant + // worst case bound for any wind ratio, airspeed, and path curvature + + // the lower bound for zero curvature and no wind OR damping ratio < 0.5 + const float period_lb = M_PI_F * roll_time_const_ / damping_; + + if (air_turn_rate * wind_factor < NPFG_EPSILON || damping_ < 0.5f) { + return period_lb; + + } else { + // the lower bound for tracking a curved path in wind with damping ratio > 0.5 + const float period_windy_curved_damped = 4.0f * M_PI_F * roll_time_const_ * damping_; + + // blend the two together as the bearing on track becomes less feasible + return period_windy_curved_damped * feas_on_track + (1.0f - feas_on_track) * period_lb; + } +} + +float DirectionalGuidance::trackProximity(const float look_ahead_ang) const +{ + const float sin_look_ahead_ang = sinf(look_ahead_ang); + return sin_look_ahead_ang * sin_look_ahead_ang; +} + +float DirectionalGuidance::trackErrorBound(const float ground_speed, const float time_const) const +{ + if (ground_speed > 1.0f) { + return ground_speed * time_const; + + } else { + // limit bound to some minimum ground speed to avoid singularities in track + // error normalization. the following equation assumes ground speed minimum = 1.0 + return 0.5f * time_const * (ground_speed * ground_speed + 1.0f); + } +} + +float DirectionalGuidance::timeConst(const float period, const float damping) const +{ + return period * damping; +} + +float DirectionalGuidance::lookAheadAngle(const float normalized_track_error) const +{ + return M_PI_2_F * (normalized_track_error - 1.0f) * (normalized_track_error - 1.0f); +} + + +matrix::Vector2f DirectionalGuidance::bearingVec(const Vector2f &unit_path_tangent, const float look_ahead_ang, + const float signed_track_error) const +{ + const float cos_look_ahead_ang = cosf(look_ahead_ang); + const float sin_look_ahead_ang = sinf(look_ahead_ang); + + Vector2f unit_path_normal(-unit_path_tangent(1), unit_path_tangent(0)); // right handed 90 deg (clockwise) turn + Vector2f unit_track_error = -((signed_track_error < 0.0f) ? -1.0f : 1.0f) * unit_path_normal; + + return cos_look_ahead_ang * unit_track_error + sin_look_ahead_ang * unit_path_tangent; +} + +float +DirectionalGuidance::bearingFeasibility(float wind_cross_bearing, const float wind_dot_bearing, const float airspeed, + const float wind_speed) const +{ + if (wind_dot_bearing < 0.0f) { + wind_cross_bearing = wind_speed; + + } else { + wind_cross_bearing = fabsf(wind_cross_bearing); + } + + float sin_arg = sinf(M_PI_F * 0.5f * math::constrain((airspeed - wind_cross_bearing) / AIRSPEED_BUFFER, 0.0f, 1.0f)); + return sin_arg * sin_arg; +} + +float DirectionalGuidance::lateralAccelFF(const Vector2f &unit_path_tangent, const Vector2f &ground_vel, + const float wind_dot_upt, const float wind_cross_upt, const float airspeed, + const float wind_speed, const float signed_track_error, + const float path_curvature) const +{ + // NOTE: all calculations within this function take place at the closet point + // on the path, as if the aircraft were already tracking the given path at + // this point with zero angular error. this allows us to evaluate curvature + // induced requirements for lateral acceleration incrementation and ramp them + // in with the track proximity and further consider the bearing feasibility + // in excess wind conditions (this is done external to this method). + + // path frame curvature is the instantaneous curvature at our current distance + // from the actual path (considering e.g. concentric circles emanating outward/inward) + const float path_frame_curvature = path_curvature / math::max(1.0f - path_curvature * signed_track_error, + fabsf(path_curvature) * MIN_RADIUS); + + // limit tangent ground speed to along track (forward moving) direction + const float tangent_ground_speed = math::max(ground_vel.dot(unit_path_tangent), 0.0f); + + const float path_frame_rate = path_frame_curvature * tangent_ground_speed; + + // speed ratio = projection of ground vel on track / projection of air velocity + // on track + const float speed_ratio = (1.0f + wind_dot_upt / math::max(projectAirspOnBearing(airspeed, wind_cross_upt), + NPFG_EPSILON)); + + // note the use of airspeed * speed_ratio as oppose to ground_speed^2 here -- + // the prior considers that we command lateral acceleration in the air mass + // relative frame while the latter does not + return airspeed * speed_ratio * path_frame_rate; +} + +float DirectionalGuidance::projectAirspOnBearing(const float airspeed, const float wind_cross_bearing) const +{ + // NOTE: wind_cross_bearing must be less than airspeed to use this function + // it is assumed that bearing feasibility is checked and found feasible (e.g. bearingIsFeasible() = true) prior to entering this method + // otherwise the return will be erroneous + return sqrtf(math::max(airspeed * airspeed - wind_cross_bearing * wind_cross_bearing, 0.0f)); +} + +float DirectionalGuidance::switchDistance(float wp_radius) const +{ + return math::min(wp_radius, track_error_bound_ * switch_distance_multiplier_); +} diff --git a/src/lib/npfg/npfg.hpp b/src/lib/npfg/DirectionalGuidance.hpp similarity index 51% rename from src/lib/npfg/npfg.hpp rename to src/lib/npfg/DirectionalGuidance.hpp index c36184ef96..691b1fd4dd 100644 --- a/src/lib/npfg/npfg.hpp +++ b/src/lib/npfg/DirectionalGuidance.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * Copyright (c) 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -32,13 +32,12 @@ ****************************************************************************/ /* - * @file npfg.hpp - * Implementation of a lateral-directional nonlinear path following guidance - * law with excess wind handling. Commands lateral acceleration and airspeed. + * @file DirectionalGuidance.hpp * - * @author Thomas Stastny + * Original Author: Thomas Stastny + * Refactored to better suite new control API: Roman Bapst * - * Notes: + * * Notes: * - The wind estimate should be dynamic enough to capture ~1-2 second length gusts, * Otherwise the performance will suffer. * @@ -57,50 +56,26 @@ * https://tstastny.github.io/pdf/tstastny_phd_thesis_wcover.pdf */ -#ifndef NPFG_H_ -#define NPFG_H_ - +#ifndef PX4_DIRECTIONALGUIDANCE_HPP +#define PX4_DIRECTIONALGUIDANCE_HPP #include #include -#include +struct DirectionalGuidanceOutput { + float course_setpoint{NAN}; + float lateral_acceleration_feedforward{NAN}; +}; -/* - * NPFG - * Lateral-directional nonlinear path following guidance logic with excess wind handling - */ -class NPFG +class DirectionalGuidance { - public: - /** - * @brief Can run - * - * Evaluation if all the necessary information are available such that npfg can produce meaningful results. - * - * @param[in] local_pos is the current vehicle local position uorb message - * @param[in] is_wind_valid flag if the wind estimation is valid - * @return estimate of certainty of the correct functionality of the npfg roll setpoint in [0, 1]. Can be used to define proper mitigation actions. - */ - float canRun(const vehicle_local_position_s &local_pos, bool is_wind_valid) const; - /* - * Computes the lateral acceleration and true airspeed references necessary to track - * a path in wind (including excess wind conditions). - * - * @param[in] curr_pos_local Current horizontal vehicle position in local coordinates [m] - * @param[in] ground_vel Vehicle ground velocity vector [m/s] - * @param[in] wind_vel Wind velocity vector [m/s] - * @param[in] unit_path_tangent Unit vector tangent to path at closest point - * in direction of path - * @param[in] position_on_path Horizontal point on the path to track described in local coordinates [m] - * @param[in] path_curvature Path curvature at closest point on track [m^-1] - */ - void guideToPath(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_vel, - const matrix::Vector2f &wind_vel, - const matrix::Vector2f &unit_path_tangent, const matrix::Vector2f &position_on_path, - const float path_curvature); + DirectionalGuidance(); + DirectionalGuidanceOutput guideToPath(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_vel, + const matrix::Vector2f &wind_vel, + const matrix::Vector2f &unit_path_tangent, const matrix::Vector2f &position_on_path, + const float path_curvature); /* * Set the nominal controller period [s]. */ @@ -122,42 +97,6 @@ public: */ void enablePeriodUB(const bool en) { en_period_ub_ = en; } - /* - * Enable minimum forward ground speed maintenance logic. - */ - void enableMinGroundSpeed(const bool en) { en_min_ground_speed_ = en; } - - /* - * Enable track keeping logic in excess wind conditions. - */ - void enableTrackKeeping(const bool en) { en_track_keeping_ = en; } - - /* - * Enable wind excess regulation. Disabling this param disables all airspeed - * reference incrementaion (airspeed reference will always be nominal). - */ - void enableWindExcessRegulation(const bool en) { en_wind_excess_regulation_ = en; } - - /* - * Set the minimum allowed forward ground speed [m/s]. - */ - void setMinGroundSpeed(float min_gsp) { min_gsp_desired_ = math::max(min_gsp, 0.0f); } - - /* - * Set the maximum value of the minimum forward ground speed command for track - * keeping (occurs at the track error boundary) [m/s]. - */ - void setMaxTrackKeepingMinGroundSpeed(float min_gsp) { min_gsp_track_keeping_max_ = math::max(min_gsp, 0.0f); } - - /* - * Set the nominal airspeed reference (true airspeed) [m/s]. - */ - void setAirspeedNom(float airsp) { airspeed_nom_ = math::max(airsp, 0.1f); } - - /* - * Set the maximum airspeed reference (true airspeed) [m/s]. - */ - void setAirspeedMax(float airsp) { airspeed_max_ = math::max(airsp, 0.1f); } /* * Set the autopilot roll response time constant [s]. @@ -165,88 +104,14 @@ public: void setRollTimeConst(float tc) { roll_time_const_ = tc; } /* - * Set the switch distance multiplier. - */ + * Set the switch distance multiplier. + */ void setSwitchDistanceMultiplier(float mult) { switch_distance_multiplier_ = math::max(mult, 0.1f); } /* * Set the period safety factor. */ void setPeriodSafetyFactor(float sf) { period_safety_factor_ = math::max(sf, 1.0f); } - - /* - * @return Controller proportional gain [rad/s] - */ - float getPGain() const { return p_gain_; } - - /* - * @return Controller time constant [s] - */ - float getTimeConst() const { return time_const_; } - - /* - * @return Adapted controller period [s] - */ - float getAdaptedPeriod() const { return adapted_period_; } - - /* - * @return Track error boundary [m] - */ - float getTrackErrorBound() const { return track_error_bound_; } - - /* - * @return Signed track error [m] - */ - float getTrackError() const { return signed_track_error_; } - - /* - * @return Airspeed reference [m/s] - */ - float getAirspeedRef() const { return airspeed_ref_; } - - /* - * @return Heading angle reference [rad] - */ - float getHeadingRef() const { return atan2f(air_vel_ref_(1), air_vel_ref_(0)); } - - /* - * @return Bearing angle [rad] - */ - float getBearing() const { return atan2f(bearing_vec_(1), bearing_vec_(0)); } - - /* - * @return Lateral acceleration command [m/s^2] - */ - float getLateralAccel() const { return lateral_accel_; } - - /* - * @return Feed-forward lateral acceleration command increment for tracking - * path curvature [m/s^2] - */ - float getLateralAccelFF() const { return lateral_accel_ff_; } - - /* - * @return Bearing feasibility [0, 1] - */ - float getBearingFeas() const { return feas_; } - - /* - * @return On-track bearing feasibility [0, 1] - */ - float getOnTrackBearingFeas() const { return feas_on_track_; } - - /* - * @return Minimum forward ground speed reference [m/s] - */ - float getMinGroundSpeedRef() const { return min_ground_speed_ref_; } - - /* - * [Copied directly from ECL_L1_Pos_Controller] - * - * Set the maximum roll angle output in radians - */ - void setRollLimit(float roll_lim_rad) { roll_lim_rad_ = roll_lim_rad; } - /* * [Copied directly from ECL_L1_Pos_Controller] * @@ -259,38 +124,21 @@ public: */ float switchDistance(float wp_radius) const; - /* - * [Copied directly from ECL_L1_Pos_Controller] - * - * Get roll angle setpoint for fixed wing. - * - * @return Roll angle (in NED frame) - */ - float getRollSetpoint() { return roll_setpoint_; } + float getCourseSetpoint() const { return course_sp_; } + float getLateralAccelerationSetpoint() const { return lateral_accel_ff_; } + float getBearingFeasibility() const { return feas_; } + float getBearingFeasibilityOnTrack() const { return feas_on_track_; } + float getSignedTrackError() const { return signed_track_error_; } + float getTrackErrorBound() const { return track_error_bound_; } + float getAdaptedPeriod() const { return adapted_period_; } private: - static constexpr float HORIZONTAL_EVH_FACTOR_COURSE_VALID{3.f}; ///< Factor of velocity standard deviation above which course calculation is considered good enough - static constexpr float HORIZONTAL_EVH_FACTOR_COURSE_INVALID{2.f}; ///< Factor of velocity standard deviation below which course calculation is considered unsafe - static constexpr float COS_HEADING_TRACK_ANGLE_NOT_PUSHED_BACK{0.09f}; ///< Cos of Heading to track angle below which it is assumed that the vehicle is not pushed back by the wind ~cos(85°) - static constexpr float COS_HEADING_TRACK_ANGLE_PUSHED_BACK{0.f}; ///< Cos of Heading to track angle above which it is assumed that the vehicle is pushed back by the wind - static constexpr float NPFG_EPSILON = 1.0e-6; // small number *bigger than machine epsilon static constexpr float MIN_RADIUS = 0.5f; // minimum effective radius (avoid singularities) [m] - static constexpr float NTE_FRACTION = 0.5f; // normalized track error fraction (must be > 0) - // ^determines at what fraction of the normalized track error the maximum track keeping forward ground speed demand is reached static constexpr float AIRSPEED_BUFFER = 1.5f; // airspeed buffer [m/s] (must be > 0) - // ^the size of the feasibility transition region at cross wind angle >= 90 deg. - // This must be non-zero to avoid jumpy airspeed incrementation while using wind - // excess handling logic. Similarly used as buffer region around zero airspeed. - - /* - * tuning - */ float period_{10.0f}; // nominal (desired) period -- user defined [s] float damping_{0.7071f}; // nominal (desired) damping ratio -- user defined - float p_gain_{0.8885f}; // proportional gain (computed from period_ and damping_) [rad/s] - float time_const_{7.071f}; // time constant (computed from period_ and damping_) [s] float adapted_period_{10.0f}; // auto-adapted period (if stability bounds enabled) [s] /* @@ -300,17 +148,9 @@ private: // guidance options bool en_period_lb_{true}; // enables automatic lower bound constraints on controller period bool en_period_ub_{true}; // enables automatic upper bound constraints on controller period (remains disabled if lower bound is disabled) - bool en_min_ground_speed_{true}; // the airspeed reference is incremented to sustain a user defined minimum forward ground speed - bool en_track_keeping_{false}; // the airspeed reference is incremented to return to the track and sustain zero ground velocity until excess wind subsides - bool en_wind_excess_regulation_{true}; // the airspeed reference is incremented to regulate the excess wind, but not overcome it ... - // ^disabling this parameter disables all other excess wind handling options, using only the nominal airspeed for reference // guidance settings - float airspeed_nom_{15.0f}; // nominal (desired) true airspeed reference (generally equivalent to cruise optimized airspeed) [m/s] - float airspeed_max_{20.0f}; // maximum true airspeed reference - the maximum achievable/allowed airspeed reference [m/s] float roll_time_const_{0.0f}; // autopilot roll response time constant [s] - float min_gsp_desired_{0.0f}; // user defined miminum desired forward ground speed [m/s] - float min_gsp_track_keeping_max_{5.0f}; // maximum, minimum forward ground speed demand from track keeping logic [m/s] // guidance parameters float switch_distance_multiplier_{0.32f}; // a value multiplied by the track error boundary resulting in a lower switch distance @@ -318,12 +158,8 @@ private: float period_safety_factor_{1.5f}; // multiplied by the minimum period for conservative lower bound /* - * internal guidance states - */ - - // speeds - float min_gsp_track_keeping_{0.0f}; // minimum forward ground speed demand from track keeping logic [m/s] - float min_ground_speed_ref_{0.0f}; // resultant minimum forward ground speed reference considering all active guidance logic [m/s] + * internal guidance states + */ //bearing feasibility float feas_{1.0f}; // continous representation of bearing feasibility in [0,1] (0=infeasible, 1=feasible) @@ -332,27 +168,23 @@ private: // track proximity float track_error_bound_{212.13f}; // the current ground speed dependent track error bound [m] float track_proximity_{0.0f}; // value in [0,1] indicating proximity to track, 0 = at track error boundary or beyond, 1 = on track - - // path following states float signed_track_error_{0.0f}; // signed track error [m] matrix::Vector2f bearing_vec_{matrix::Vector2f{1.0f, 0.0f}}; // bearing unit vector + float course_sp_{0.f}; // course setpoint [rad] + float lateral_accel_ff_{0.f}; // lateral acceleration feedforward [m/s^2] /* - * guidance outputs + * Cacluates a continuous representation of the bearing feasibility from [0,1]. + * 0 = infeasible, 1 = fully feasible, partial feasibility in between. + * + * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] + * @param[in] wind_dot_bearing 2D dot product of wind velocity and bearing vector [m/s] + * @param[in] airspeed Vehicle true airspeed [m/s] + * @param[in] wind_speed Wind speed [m/s] + * @return bearing feasibility */ - - float airspeed_ref_{15.0f}; // true airspeed reference [m/s] - matrix::Vector2f air_vel_ref_{matrix::Vector2f{15.0f, 0.0f}}; // true air velocity reference vector [m/s] - float lateral_accel_{0.0f}; // lateral acceleration reference [m/s^2] - float lateral_accel_ff_{0.0f}; // lateral acceleration demand to maintain path curvature [m/s^2] - - /* - * ECL_L1_Pos_Controller functionality - */ - - float roll_lim_rad_{math::radians(30.0f)}; // maximum roll angle [rad] - float roll_setpoint_{0.0f}; // current roll angle setpoint [rad] - + float bearingFeasibility(float wind_cross_bearing, const float wind_dot_bearing, const float airspeed, + const float wind_speed) const; /* * Adapts the controller period considering user defined inputs, current flight * condition, path properties, and stability bounds. @@ -371,7 +203,6 @@ private: float adaptPeriod(const float ground_speed, const float airspeed, const float wind_speed, const float track_error, const float path_curvature, const matrix::Vector2f &wind_vel, const matrix::Vector2f &unit_path_tangent, const float feas_on_track) const; - /* * Returns normalized (unitless) and constrained track error [0,1]. * @@ -435,17 +266,6 @@ private: */ float trackErrorBound(const float ground_speed, const float time_const) const; - /* - * Calculates the required controller proportional gain to achieve the desired - * system period and damping ratio. NOTE: actual period and damping will vary - * when following paths with curvature in wind. - * - * @param[in] period Desired system period [s] - * @param[in] damping Desired system damping ratio - * @return Proportional gain [rad/s] - */ - float pGain(const float period, const float damping) const; - /* * Calculates the required controller time constant to achieve the desired * system period and damping ratio. NOTE: actual period and damping will vary @@ -465,7 +285,6 @@ private: * @return Look ahead angle [rad] */ float lookAheadAngle(const float normalized_track_error) const; - /* * Calculates the bearing vector and track proximity transitioning variable * from the look-ahead angle mapping. @@ -481,33 +300,6 @@ private: matrix::Vector2f bearingVec(const matrix::Vector2f &unit_path_tangent, const float look_ahead_ang, const float signed_track_error) const; - /* - * Calculates the minimum forward ground speed demand for minimum forward - * ground speed maintanence as well as track keeping logic. - * - * @param[in] normalized_track_error Normalized track error (track error / track error boundary) - * @param[in] feas Bearing feasibility - * @return Minimum forward ground speed demand [m/s] - */ - float minGroundSpeed(const float normalized_track_error, const float feas); - - /* - * Determines a reference air velocity *without curvature compensation, but - * including "optimal" true airspeed reference compensation in excess wind conditions. - * Nominal and maximum true airspeed member variables must be set before using this method. - * - * @param[in] wind_vel Wind velocity vector [m/s] - * @param[in] bearing_vec Bearing vector - * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] - * @param[in] wind_dot_bearing 2D dot product of wind velocity and bearing vector [m/s] - * @param[in] wind_speed Wind speed [m/s] - * @param[in] min_ground_speed Minimum commanded forward ground speed [m/s] - * @return Air velocity vector [m/s] - */ - matrix::Vector2f refAirVelocity(const matrix::Vector2f &wind_vel, const matrix::Vector2f &bearing_vec, - const float wind_cross_bearing, const float wind_dot_bearing, const float wind_speed, - const float min_ground_speed) const; - /* * Projection of the air velocity vector onto the bearing line considering * a connected wind triangle. @@ -517,58 +309,6 @@ private: * @return Projection of air velocity vector on bearing vector [m/s] */ float projectAirspOnBearing(const float airspeed, const float wind_cross_bearing) const; - - /* - * Check for binary bearing feasibility. - * - * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] - * @param[in] wind_dot_bearing 2D dot product of wind velocity and bearing vector [m/s] - * @param[in] airspeed Vehicle true airspeed [m/s] - * @param[in] wind_speed Wind speed [m/s] - * @return Binary bearing feasibility: 1 if feasible, 0 if infeasible - */ - int bearingIsFeasible(const float wind_cross_bearing, const float wind_dot_bearing, const float airspeed, - const float wind_speed) const; - - /* - * Air velocity solution for a given wind velocity and bearing vector assuming - * a "high speed" (not backwards) solution in the excess wind case. - * - * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] - * @param[in] airsp_dot_bearing 2D dot product of air velocity (solution) and bearing vector [m/s] - * @param[in] bearing_vec Bearing vector - * @return Air velocity vector [m/s] - */ - matrix::Vector2f solveWindTriangle(const float wind_cross_bearing, const float airsp_dot_bearing, - const matrix::Vector2f &bearing_vec) const; - - - /* - * Air velocity solution for an infeasible bearing. - * - * @param[in] wind_vel Wind velocity vector [m/s] - * @param[in] bearing_vec Bearing vector - * @param[in] wind_speed Wind speed [m/s] - * @param[in] airspeed Vehicle true airspeed [m/s] - * @return Air velocity vector [m/s] - */ - matrix::Vector2f infeasibleAirVelRef(const matrix::Vector2f &wind_vel, const matrix::Vector2f &bearing_vec, - const float wind_speed, const float airspeed) const; - - - /* - * Cacluates a continuous representation of the bearing feasibility from [0,1]. - * 0 = infeasible, 1 = fully feasible, partial feasibility in between. - * - * @param[in] wind_cross_bearing 2D cross product of wind velocity and bearing vector [m/s] - * @param[in] wind_dot_bearing 2D dot product of wind velocity and bearing vector [m/s] - * @param[in] airspeed Vehicle true airspeed [m/s] - * @param[in] wind_speed Wind speed [m/s] - * @return bearing feasibility - */ - float bearingFeasibility(float wind_cross_bearing, const float wind_dot_bearing, const float airspeed, - const float wind_speed) const; - /* * Calculates an additional feed-forward lateral acceleration demand considering * the path curvature. @@ -588,29 +328,6 @@ private: const float wind_dot_upt, const float wind_cross_upt, const float airspeed, const float wind_speed, const float signed_track_error, const float path_curvature) const; - /* - * Calculates a lateral acceleration demand from the heading error. - * (does not consider path curvature) - * - * @param[in] air_vel Vechile air velocity vector [m/s] - * @param[in] air_vel_ref Reference air velocity vector [m/s] - * @param[in] airspeed Vehicle true airspeed [m/s] - * @return Lateral acceleration demand [m/s^2] - */ - float lateralAccel(const matrix::Vector2f &air_vel, const matrix::Vector2f &air_vel_ref, - const float airspeed) const; +}; - /******************************************************************************* - * PX4 POSITION SETPOINT INTERFACE FUNCTIONS - */ - - /** - * [Copied directly from ECL_L1_Pos_Controller] - * - * Update roll angle setpoint. This will also apply slew rate limits if set. - */ - void updateRollSetpoint(); - -}; // class NPFG - -#endif // NPFG_H_ +#endif //PX4_DIRECTIONALGUIDANCE_HPP diff --git a/src/lib/npfg/npfg.cpp b/src/lib/npfg/npfg.cpp deleted file mode 100644 index fdcfa570b0..0000000000 --- a/src/lib/npfg/npfg.cpp +++ /dev/null @@ -1,508 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* - * @file npfg.cpp - * Implementation of a lateral-directional nonlinear path following guidance - * law with excess wind handling. Commands lateral acceleration and airspeed. - * - * Authors and acknowledgements in header. - */ - -#include "npfg.hpp" -#include -#include -#include - -using matrix::Vector2d; -using matrix::Vector2f; - -float NPFG::canRun(const vehicle_local_position_s &local_pos, const bool is_wind_valid) const -{ - if (is_wind_valid) { - // If we have a valid wind estimate, npfg is able to handle all degenerated cases - return 1.f; - } - - // NPFG can run without wind information as long as the system is not flying backwards and has a minimal ground speed - // Check the minimal ground speed. if it is greater than twice the standard deviation, we assume that we can infer a valid track angle - const Vector2f ground_vel(local_pos.vx, local_pos.vy); - const float ground_speed(ground_vel.norm()); - const float low_ground_speed_factor(math::constrain((ground_speed - HORIZONTAL_EVH_FACTOR_COURSE_INVALID * - local_pos.evh) / ((HORIZONTAL_EVH_FACTOR_COURSE_VALID - HORIZONTAL_EVH_FACTOR_COURSE_INVALID)*local_pos.evh), - 0.f, 1.f)); - - // Check that the angle between heading and track is not off too much. if it is greater than 90° we will be pushed back from the wind and the npfg will propably give a roll command in the wrong direction. - const Vector2f heading_vector(matrix::Dcm2f(local_pos.heading)*Vector2f({1.f, 0.f})); - const Vector2f ground_vel_norm(ground_vel.normalized()); - const float flying_forward_factor(math::constrain((heading_vector.dot(ground_vel_norm) - - COS_HEADING_TRACK_ANGLE_PUSHED_BACK) / ((COS_HEADING_TRACK_ANGLE_NOT_PUSHED_BACK - - COS_HEADING_TRACK_ANGLE_PUSHED_BACK)), - 0.f, 1.f)); - - return flying_forward_factor * low_ground_speed_factor; -} - -void NPFG::guideToPath(const matrix::Vector2f &curr_pos_local, const Vector2f &ground_vel, const Vector2f &wind_vel, - const Vector2f &unit_path_tangent, - const Vector2f &position_on_path, const float path_curvature) -{ - const float ground_speed = ground_vel.norm(); - - const Vector2f air_vel = ground_vel - wind_vel; - const float airspeed = air_vel.norm(); - - const float wind_speed = wind_vel.norm(); - - const Vector2f path_pos_to_vehicle{curr_pos_local - position_on_path}; - signed_track_error_ = unit_path_tangent.cross(path_pos_to_vehicle); - - // on-track wind triangle projections - const float wind_cross_upt = wind_vel.cross(unit_path_tangent); - const float wind_dot_upt = wind_vel.dot(unit_path_tangent); - - // calculate the bearing feasibility on the track at the current closest point - feas_on_track_ = bearingFeasibility(wind_cross_upt, wind_dot_upt, airspeed, wind_speed); - - const float track_error = fabsf(signed_track_error_); - - // update control parameters considering upper and lower stability bounds (if enabled) - // must be called before trackErrorBound() as it updates time_const_ - adapted_period_ = adaptPeriod(ground_speed, airspeed, wind_speed, track_error, - path_curvature, wind_vel, unit_path_tangent, feas_on_track_); - p_gain_ = pGain(adapted_period_, damping_); - time_const_ = timeConst(adapted_period_, damping_); - - // track error bound is dynamic depending on ground speed - track_error_bound_ = trackErrorBound(ground_speed, time_const_); - const float normalized_track_error = normalizedTrackError(track_error, track_error_bound_); - - // look ahead angle based solely on track proximity - const float look_ahead_ang = lookAheadAngle(normalized_track_error); - - track_proximity_ = trackProximity(look_ahead_ang); - - bearing_vec_ = bearingVec(unit_path_tangent, look_ahead_ang, signed_track_error_); - - // wind triangle projections - const float wind_cross_bearing = wind_vel.cross(bearing_vec_); - const float wind_dot_bearing = wind_vel.dot(bearing_vec_); - - // continuous representation of the bearing feasibility - feas_ = bearingFeasibility(wind_cross_bearing, wind_dot_bearing, airspeed, wind_speed); - - // we consider feasibility of both the current bearing as well as that on the track at the current closest point - const float feas_combined = feas_ * feas_on_track_; - - min_ground_speed_ref_ = minGroundSpeed(normalized_track_error, feas_combined); - - // reference air velocity with directional feedforward effect for following - // curvature in wind and magnitude incrementation depending on minimum ground - // speed violations and/or high wind conditions in general - air_vel_ref_ = refAirVelocity(wind_vel, bearing_vec_, wind_cross_bearing, - wind_dot_bearing, wind_speed, min_ground_speed_ref_); - airspeed_ref_ = air_vel_ref_.norm(); - - // lateral acceleration demand based on heading error - const float lateral_accel = lateralAccel(air_vel, air_vel_ref_, airspeed); - - // lateral acceleration needed to stay on curved track (assuming no heading error) - lateral_accel_ff_ = lateralAccelFF(unit_path_tangent, ground_vel, wind_dot_upt, - wind_cross_upt, airspeed, wind_speed, signed_track_error_, path_curvature); - - // total lateral acceleration to drive aircaft towards track as well as account - // for path curvature. The full effect of the feed-forward acceleration is smoothly - // ramped in as the vehicle approaches the track and is further smoothly - // zeroed out as the bearing becomes infeasible. - lateral_accel_ = lateral_accel + feas_combined * track_proximity_ * lateral_accel_ff_; - - updateRollSetpoint(); -} // guideToPath - -float NPFG::adaptPeriod(const float ground_speed, const float airspeed, const float wind_speed, - const float track_error, const float path_curvature, const Vector2f &wind_vel, - const Vector2f &unit_path_tangent, const float feas_on_track) const -{ - float period = period_; - const float air_turn_rate = fabsf(path_curvature * airspeed); - const float wind_factor = windFactor(airspeed, wind_speed); - - if (en_period_lb_ && roll_time_const_ > NPFG_EPSILON) { - // lower bound for period not considering path curvature - const float period_lb_zero_curvature = periodLowerBound(0.0f, wind_factor, feas_on_track) * period_safety_factor_; - - // lower bound for period *considering path curvature - float period_lb = periodLowerBound(air_turn_rate, wind_factor, feas_on_track) * period_safety_factor_; - - // calculate the time constant and track error bound considering the zero - // curvature, lower-bounded period and subsequently recalculate the normalized - // track error - const float time_const = timeConst(period_lb_zero_curvature, damping_); - const float track_error_bound = trackErrorBound(ground_speed, time_const); - const float normalized_track_error = normalizedTrackError(track_error, track_error_bound); - - // calculate nominal track proximity with lower bounded time constant - // (only a numerical solution can find corresponding track proximity - // and adapted gains simultaneously) - const float look_ahead_ang = lookAheadAngle(normalized_track_error); - const float track_proximity = trackProximity(look_ahead_ang); - - // linearly ramp in curvature dependent lower bound with track proximity - period_lb = period_lb * track_proximity + (1.0f - track_proximity) * period_lb_zero_curvature; - - // lower bounded period - period = math::max(period_lb, period); - - // only allow upper bounding ONLY if lower bounding is enabled (is otherwise - // dangerous to allow period decrements without stability checks). - // NOTE: if the roll time constant is not accurately known, lower-bound - // checks may be too optimistic and reducing the period can still destabilize - // the system! enable this feature at your own risk. - if (en_period_ub_) { - - const float period_ub = periodUpperBound(air_turn_rate, wind_factor, feas_on_track); - - if (en_period_ub_ && PX4_ISFINITE(period_ub) && period > period_ub) { - // NOTE: if the roll time constant is not accurately known, reducing - // the period here can destabilize the system! - // enable this feature at your own risk! - - // upper bound the period (for track keeping stability), prefer lower bound if violated - const float period_adapted = math::max(period_lb, period_ub); - - // transition from the nominal period to the adapted period as we get - // closer to the track - period = period_adapted * track_proximity + (1.0f - track_proximity) * period; - } - } - } - - return period; -} // adaptPeriod - -float NPFG::normalizedTrackError(const float track_error, const float track_error_bound) const -{ - return math::constrain(track_error / track_error_bound, 0.0f, 1.0f); -} - -float NPFG::windFactor(const float airspeed, const float wind_speed) const -{ - // See [TODO: include citation] for definition/elaboration of this approximation. - if (wind_speed > airspeed || airspeed < NPFG_EPSILON) { - return 2.0f; - - } else { - return 2.0f * (1.0f - sqrtf(1.0f - math::min(1.0f, wind_speed / airspeed))); - } -} // windFactor - -float NPFG::periodUpperBound(const float air_turn_rate, const float wind_factor, const float feas_on_track) const -{ - if (air_turn_rate * wind_factor > NPFG_EPSILON) { - // multiply air turn rate by feasibility on track to zero out when we anyway - // should not consider the curvature - return 4.0f * M_PI_F * damping_ / (air_turn_rate * wind_factor * feas_on_track); - } - - return INFINITY; -} // periodUB - -float NPFG::periodLowerBound(const float air_turn_rate, const float wind_factor, const float feas_on_track) const -{ - // this method considers a "conservative" lower period bound, i.e. a constant - // worst case bound for any wind ratio, airspeed, and path curvature - - // the lower bound for zero curvature and no wind OR damping ratio < 0.5 - const float period_lb = M_PI_F * roll_time_const_ / damping_; - - if (air_turn_rate * wind_factor < NPFG_EPSILON || damping_ < 0.5f) { - return period_lb; - - } else { - // the lower bound for tracking a curved path in wind with damping ratio > 0.5 - const float period_windy_curved_damped = 4.0f * M_PI_F * roll_time_const_ * damping_; - - // blend the two together as the bearing on track becomes less feasible - return period_windy_curved_damped * feas_on_track + (1.0f - feas_on_track) * period_lb; - } -} // periodLB - -float NPFG::trackProximity(const float look_ahead_ang) const -{ - const float sin_look_ahead_ang = sinf(look_ahead_ang); - return sin_look_ahead_ang * sin_look_ahead_ang; -} // trackProximity - -float NPFG::trackErrorBound(const float ground_speed, const float time_const) const -{ - if (ground_speed > 1.0f) { - return ground_speed * time_const; - - } else { - // limit bound to some minimum ground speed to avoid singularities in track - // error normalization. the following equation assumes ground speed minimum = 1.0 - return 0.5f * time_const * (ground_speed * ground_speed + 1.0f); - } -} // trackErrorBound - -float NPFG::pGain(const float period, const float damping) const -{ - return 4.0f * M_PI_F * damping / period; -} // pGain - -float NPFG::timeConst(const float period, const float damping) const -{ - return period * damping; -} // timeConst - -float NPFG::lookAheadAngle(const float normalized_track_error) const -{ - return M_PI_2_F * (normalized_track_error - 1.0f) * (normalized_track_error - 1.0f); -} // lookAheadAngle - -Vector2f NPFG::bearingVec(const Vector2f &unit_path_tangent, const float look_ahead_ang, - const float signed_track_error) const -{ - const float cos_look_ahead_ang = cosf(look_ahead_ang); - const float sin_look_ahead_ang = sinf(look_ahead_ang); - - Vector2f unit_path_normal(-unit_path_tangent(1), unit_path_tangent(0)); // right handed 90 deg (clockwise) turn - Vector2f unit_track_error = -((signed_track_error < 0.0f) ? -1.0f : 1.0f) * unit_path_normal; - - return cos_look_ahead_ang * unit_track_error + sin_look_ahead_ang * unit_path_tangent; -} // bearingVec - -float NPFG::minGroundSpeed(const float normalized_track_error, const float feas) -{ - // minimum ground speed demand from track keeping logic - min_gsp_track_keeping_ = 0.0f; - - if (en_track_keeping_ && en_wind_excess_regulation_) { - // zero out track keeping speed increment when bearing is feasible - // maximum track keeping speed increment is applied until we are within - // a user defined fraction of the normalized track error - min_gsp_track_keeping_ = (1.0f - feas) * min_gsp_track_keeping_max_ * math::constrain( - normalized_track_error / NTE_FRACTION, 0.0f, - 1.0f); - } - - // minimum ground speed demand from minimum forward ground speed user setting - float min_gsp_desired = 0.0f; - - if (en_min_ground_speed_ && en_wind_excess_regulation_) { - min_gsp_desired = min_gsp_desired_; - } - - return math::max(min_gsp_track_keeping_, min_gsp_desired); -} // minGroundSpeed - -Vector2f NPFG::refAirVelocity(const Vector2f &wind_vel, const Vector2f &bearing_vec, - const float wind_cross_bearing, const float wind_dot_bearing, const float wind_speed, - const float min_ground_speed) const -{ - Vector2f air_vel_ref; - - if (min_ground_speed > wind_dot_bearing && (en_min_ground_speed_ || en_track_keeping_) && en_wind_excess_regulation_) { - // minimum ground speed and/or track keeping - - // airspeed required to achieve minimum ground speed along bearing vector - const float airspeed_min = sqrtf((min_ground_speed - wind_dot_bearing) * (min_ground_speed - wind_dot_bearing) + - wind_cross_bearing * wind_cross_bearing); - - if (airspeed_min > airspeed_max_) { - if (bearingIsFeasible(wind_cross_bearing, wind_dot_bearing, airspeed_max_, wind_speed)) { - // we will not maintain the minimum ground speed, but can still achieve the bearing at maximum airspeed - const float airsp_dot_bearing = projectAirspOnBearing(airspeed_max_, wind_cross_bearing); - air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vec); - - } else { - // bearing is maximally infeasible, employ mitigation law - air_vel_ref = infeasibleAirVelRef(wind_vel, bearing_vec, wind_speed, airspeed_max_); - } - - } else if (airspeed_min > airspeed_nom_) { - // the minimum ground speed is achievable within the nom - max airspeed range - // solve wind triangle with for air velocity reference with minimum airspeed - const float airsp_dot_bearing = projectAirspOnBearing(airspeed_min, wind_cross_bearing); - air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vec); - - } else { - // the minimum required airspeed is less than nominal, so we can track the bearing and minimum - // ground speed with our nominal airspeed reference - const float airsp_dot_bearing = projectAirspOnBearing(airspeed_nom_, wind_cross_bearing); - air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vec); - } - - } else { - // wind excess regulation and/or mitigation - - if (bearingIsFeasible(wind_cross_bearing, wind_dot_bearing, airspeed_nom_, wind_speed)) { - // bearing is nominally feasible, solve wind triangle for air velocity reference using nominal airspeed - const float airsp_dot_bearing = projectAirspOnBearing(airspeed_nom_, wind_cross_bearing); - air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vec); - - } else if (bearingIsFeasible(wind_cross_bearing, wind_dot_bearing, airspeed_max_, wind_speed) - && en_wind_excess_regulation_) { - // bearing is maximally feasible - if (wind_dot_bearing <= 0.0f) { - // we only increment the airspeed to regulate, but not overcome, excess wind - // NOTE: in the terminal condition, this will result in a zero ground velocity configuration - air_vel_ref = wind_vel; - - } else { - // the bearing is achievable within the nom - max airspeed range - // solve wind triangle with for air velocity reference with minimum airspeed - const float airsp_dot_bearing = 0.0f; // right angle to the bearing line gives minimal airspeed usage - air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vec); - } - - } else { - // bearing is maximally infeasible, employ mitigation law - const float airspeed_input = (en_wind_excess_regulation_) ? airspeed_max_ : airspeed_nom_; - air_vel_ref = infeasibleAirVelRef(wind_vel, bearing_vec, wind_speed, airspeed_input); - } - } - - return air_vel_ref; -} // refAirVelocity - -float NPFG::projectAirspOnBearing(const float airspeed, const float wind_cross_bearing) const -{ - // NOTE: wind_cross_bearing must be less than airspeed to use this function - // it is assumed that bearing feasibility is checked and found feasible (e.g. bearingIsFeasible() = true) prior to entering this method - // otherwise the return will be erroneous - return sqrtf(math::max(airspeed * airspeed - wind_cross_bearing * wind_cross_bearing, 0.0f)); -} // projectAirspOnBearing - -int NPFG::bearingIsFeasible(const float wind_cross_bearing, const float wind_dot_bearing, const float airspeed, - const float wind_speed) const -{ - return (fabsf(wind_cross_bearing) < airspeed) && ((wind_dot_bearing > 0.0f) || (wind_speed < airspeed)); -} // bearingIsFeasible - -Vector2f NPFG::solveWindTriangle(const float wind_cross_bearing, const float airsp_dot_bearing, - const Vector2f &bearing_vec) const -{ - // essentially a 2D rotation with the speeds (magnitudes) baked in - return Vector2f{airsp_dot_bearing * bearing_vec(0) - wind_cross_bearing * bearing_vec(1), - wind_cross_bearing * bearing_vec(0) + airsp_dot_bearing * bearing_vec(1)}; -} // solveWindTriangle - -Vector2f NPFG::infeasibleAirVelRef(const Vector2f &wind_vel, const Vector2f &bearing_vec, const float wind_speed, - const float airspeed) const -{ - // NOTE: wind speed must be greater than airspeed, and airspeed must be greater than zero to use this function - // it is assumed that bearing feasibility is checked and found infeasible (e.g. bearingIsFeasible() = false) prior to entering this method - // otherwise the normalization of the air velocity vector could have a division by zero - Vector2f air_vel_ref = sqrtf(math::max(wind_speed * wind_speed - airspeed * airspeed, 0.0f)) * bearing_vec - wind_vel; - return air_vel_ref.normalized() * airspeed; -} // infeasibleAirVelRef - -float NPFG::bearingFeasibility(float wind_cross_bearing, const float wind_dot_bearing, const float airspeed, - const float wind_speed) const -{ - if (wind_dot_bearing < 0.0f) { - wind_cross_bearing = wind_speed; - - } else { - wind_cross_bearing = fabsf(wind_cross_bearing); - } - - float sin_arg = sinf(M_PI_F * 0.5f * math::constrain((airspeed - wind_cross_bearing) / AIRSPEED_BUFFER, 0.0f, 1.0f)); - return sin_arg * sin_arg; -} // bearingFeasibility - -float NPFG::lateralAccelFF(const Vector2f &unit_path_tangent, const Vector2f &ground_vel, - const float wind_dot_upt, const float wind_cross_upt, const float airspeed, - const float wind_speed, const float signed_track_error, const float path_curvature) const -{ - // NOTE: all calculations within this function take place at the closet point - // on the path, as if the aircraft were already tracking the given path at - // this point with zero angular error. this allows us to evaluate curvature - // induced requirements for lateral acceleration incrementation and ramp them - // in with the track proximity and further consider the bearing feasibility - // in excess wind conditions (this is done external to this method). - - // path frame curvature is the instantaneous curvature at our current distance - // from the actual path (considering e.g. concentric circles emanating outward/inward) - const float path_frame_curvature = path_curvature / math::max(1.0f - path_curvature * signed_track_error, - fabsf(path_curvature) * MIN_RADIUS); - - // limit tangent ground speed to along track (forward moving) direction - const float tangent_ground_speed = math::max(ground_vel.dot(unit_path_tangent), 0.0f); - - const float path_frame_rate = path_frame_curvature * tangent_ground_speed; - - // speed ratio = projection of ground vel on track / projection of air velocity - // on track - const float speed_ratio = (1.0f + wind_dot_upt / math::max(projectAirspOnBearing(airspeed, wind_cross_upt), - NPFG_EPSILON)); - - // note the use of airspeed * speed_ratio as oppose to ground_speed^2 here -- - // the prior considers that we command lateral acceleration in the air mass - // relative frame while the latter does not - return airspeed * speed_ratio * path_frame_rate; -} // lateralAccelFF - -float NPFG::lateralAccel(const Vector2f &air_vel, const Vector2f &air_vel_ref, const float airspeed) const -{ - // lateral acceleration demand only from the heading error - - const float dot_air_vel_err = air_vel.dot(air_vel_ref); - const float cross_air_vel_err = air_vel.cross(air_vel_ref); - - if (dot_air_vel_err < 0.0f) { - // hold max lateral acceleration command above 90 deg heading error - return p_gain_ * ((cross_air_vel_err < 0.0f) ? -airspeed : airspeed); - - } else { - // airspeed/airspeed_ref is used to scale any incremented airspeed reference back to the current airspeed - // for acceleration commands in a "feedback" sense (i.e. at the current vehicle airspeed) - return p_gain_ * cross_air_vel_err / airspeed_ref_; - } -} // lateralAccel - -float NPFG::switchDistance(float wp_radius) const -{ - return math::min(wp_radius, track_error_bound_ * switch_distance_multiplier_); -} // switchDistance - -void NPFG::updateRollSetpoint() -{ - float roll_new = atanf(lateral_accel_ * 1.0f / CONSTANTS_ONE_G); - roll_new = math::constrain(roll_new, -roll_lim_rad_, roll_lim_rad_); - - if (PX4_ISFINITE(roll_new)) { - roll_setpoint_ = roll_new; - } -} // updateRollSetpoint diff --git a/src/modules/fw_lateral_longitudinal_control/CMakeLists.txt b/src/modules/fw_lateral_longitudinal_control/CMakeLists.txt new file mode 100644 index 0000000000..7642594b7a --- /dev/null +++ b/src/modules/fw_lateral_longitudinal_control/CMakeLists.txt @@ -0,0 +1,15 @@ +set(CONTROL_DEPENDENCIES + npfg + tecs +) + + +px4_add_module( + MODULE modules__fw_lateral_longitudinal_control + MAIN fw_lat_lon_control + SRCS + FwLateralLongitudinalControl.cpp + FwLateralLongitudinalControl.hpp + DEPENDS + ${CONTROL_DEPENDENCIES} +) diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp new file mode 100644 index 0000000000..eb92670ffa --- /dev/null +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp @@ -0,0 +1,841 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "FwLateralLongitudinalControl.hpp" +#include + +using math::constrain; +using math::max; +using math::radians; + +using matrix::Dcmf; +using matrix::Eulerf; +using matrix::Quatf; +using matrix::Vector2f; + +// [m/s] maximum reference altitude rate threshhold +static constexpr float MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT = 0.1f; +// [us] time after which the wind estimate is disabled if no longer updating +static constexpr hrt_abstime WIND_EST_TIMEOUT = 10_s; +// [s] slew rate with which we change altitude time constant +static constexpr float TECS_ALT_TIME_CONST_SLEW_RATE = 1.0f; + +static constexpr float HORIZONTAL_EVH_FACTOR_COURSE_VALID{3.f}; ///< Factor of velocity standard deviation above which course calculation is considered good enough +static constexpr float HORIZONTAL_EVH_FACTOR_COURSE_INVALID{2.f}; ///< Factor of velocity standard deviation below which course calculation is considered unsafe +static constexpr float COS_HEADING_TRACK_ANGLE_NOT_PUSHED_BACK{0.09f}; ///< Cos of Heading to track angle below which it is assumed that the vehicle is not pushed back by the wind ~cos(85°) +static constexpr float COS_HEADING_TRACK_ANGLE_PUSHED_BACK{0.f}; ///< Cos of Heading to track angle above which it is assumed that the vehicle is pushed back by the wind + +// [s] Timeout that has to pass in roll-constraining failsafe before warning is triggered +static constexpr uint64_t ROLL_WARNING_TIMEOUT = 2_s; + +// [-] Can-run threshold needed to trigger the roll-constraining failsafe warning +static constexpr float ROLL_WARNING_CAN_RUN_THRESHOLD = 0.9f; + +// [m/s/s] slew rate limit for airspeed setpoint changes +static constexpr float ASPD_SP_SLEW_RATE = 1.f; + +FwLateralLongitudinalControl::FwLateralLongitudinalControl(bool is_vtol) : + ModuleParams(nullptr), + WorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers), + _attitude_sp_pub(is_vtol ? ORB_ID(fw_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)), + _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")) +{ + _tecs_status_pub.advertise(); + _flight_phase_estimation_pub.advertise(); + _fixed_wing_lateral_status_pub.advertise(); + parameters_update(); + _airspeed_slew_rate_controller.setSlewRate(ASPD_SP_SLEW_RATE); +} + +FwLateralLongitudinalControl::~FwLateralLongitudinalControl() +{ + perf_free(_loop_perf); +} +void +FwLateralLongitudinalControl::parameters_update() +{ + updateParams(); + _performance_model.updateParameters(); + _performance_model.runSanityChecks(); + + _tecs.set_max_climb_rate(_performance_model.getMaximumClimbRate(_air_density)); + _tecs.set_max_sink_rate(_param_fw_t_sink_max.get()); + _tecs.set_min_sink_rate(_performance_model.getMinimumSinkRate(_air_density)); + _tecs.set_equivalent_airspeed_trim(_performance_model.getCalibratedTrimAirspeed()); + _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); + _tecs.set_equivalent_airspeed_max(_performance_model.getMaximumCalibratedAirspeed()); + _tecs.set_throttle_damp(_param_fw_t_thr_damping.get()); + _tecs.set_integrator_gain_throttle(_param_fw_t_thr_integ.get()); + _tecs.set_integrator_gain_pitch(_param_fw_t_I_gain_pit.get()); + _tecs.set_throttle_slewrate(_param_fw_thr_slew_max.get()); + _tecs.set_vertical_accel_limit(_param_fw_t_vert_acc.get()); + _tecs.set_roll_throttle_compensation(_param_fw_t_rll2thr.get()); + _tecs.set_pitch_damping(_param_fw_t_ptch_damp.get()); + _tecs.set_altitude_error_time_constant(_param_fw_t_h_error_tc.get()); + _tecs.set_fast_descend_altitude_error(_param_fw_t_fast_alt_err.get()); + _tecs.set_altitude_rate_ff(_param_fw_t_hrate_ff.get()); + _tecs.set_airspeed_error_time_constant(_param_fw_t_tas_error_tc.get()); + _tecs.set_ste_rate_time_const(_param_ste_rate_time_const.get()); + _tecs.set_seb_rate_ff_gain(_param_seb_rate_ff.get()); + _tecs.set_airspeed_measurement_std_dev(_param_speed_standard_dev.get()); + _tecs.set_airspeed_rate_measurement_std_dev(_param_speed_rate_standard_dev.get()); + _tecs.set_airspeed_filter_process_std_dev(_param_process_noise_standard_dev.get()); + + _roll_slew_rate.setSlewRate(radians(_param_fw_pn_r_slew_max.get())); + + _tecs_alt_time_const_slew_rate.setSlewRate(TECS_ALT_TIME_CONST_SLEW_RATE); + _tecs_alt_time_const_slew_rate.setForcedValue(_param_fw_t_h_error_tc.get() * _param_fw_thrtc_sc.get()); +} + +void FwLateralLongitudinalControl::Run() +{ + if (should_exit()) { + _local_pos_sub.unregisterCallback(); + exit_and_cleanup(); + return; + } + + perf_begin(_loop_perf); + + /* only run controller if position changed */ + // check for parameter updates + if (_parameter_update_sub.updated()) { + // clear update + parameter_update_s pupdate; + _parameter_update_sub.copy(&pupdate); + + // update parameters from storage + parameters_update(); + } + + if (_local_pos_sub.update(&_local_pos)) { + + const float control_interval = math::constrain((_local_pos.timestamp - _last_time_loop_ran) * 1e-6f, + 0.001f, 0.1f); + _last_time_loop_ran = _local_pos.timestamp; + + updateControllerConfiguration(); + + _tecs.set_speed_weight(_long_configuration.speed_weight); + updateTECSAltitudeTimeConstant(checkLowHeightConditions() + || _long_configuration.enforce_low_height_condition, control_interval); + _tecs.set_altitude_error_time_constant(_tecs_alt_time_const_slew_rate.getState()); + + if (_vehicle_air_data_sub.updated()) { + _vehicle_air_data_sub.update(); + _air_density = PX4_ISFINITE(_vehicle_air_data_sub.get().rho) ? _vehicle_air_data_sub.get().rho : _air_density; + _tecs.set_max_climb_rate(_performance_model.getMaximumClimbRate(_air_density)); + _tecs.set_min_sink_rate(_performance_model.getMinimumSinkRate(_air_density)); + } + + if (_vehicle_landed_sub.updated()) { + vehicle_land_detected_s landed{}; + _vehicle_landed_sub.copy(&landed); + _landed = landed.landed; + } + + _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_UNKNOWN; + + _vehicle_status_sub.update(); + _control_mode_sub.update(); + update_control_state(); + + if (_control_mode_sub.get().flag_control_manual_enabled && _control_mode_sub.get().flag_control_altitude_enabled + && _local_pos.z_reset_counter != _z_reset_counter) { + if (_control_mode_sub.get().flag_control_altitude_enabled && _local_pos.z_reset_counter != _z_reset_counter) { + // make TECS accept step in altitude and demanded altitude + _tecs.handle_alt_step(_long_control_state.altitude_msl, _long_control_state.height_rate); + } + } + + const bool should_run = (_control_mode_sub.get().flag_control_position_enabled || + _control_mode_sub.get().flag_control_velocity_enabled || + _control_mode_sub.get().flag_control_acceleration_enabled || + _control_mode_sub.get().flag_control_altitude_enabled || + _control_mode_sub.get().flag_control_climb_rate_enabled) && + (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING + || _vehicle_status_sub.get().in_transition_mode); + + if (should_run) { + + // ----- Longitudinal ------ + float pitch_sp{NAN}; + float throttle_sp{NAN}; + + if (_fw_longitudinal_ctrl_sub.updated()) { + _fw_longitudinal_ctrl_sub.copy(&_long_control_sp); + } + + const float airspeed_sp_eas = adapt_airspeed_setpoint(control_interval, _long_control_sp.equivalent_airspeed, + _min_airspeed_from_guidance, _lateral_control_state.wind_speed.length()); + + // If the both altitude and height rate are set, set altitude setpoint to NAN + const float altitude_sp = PX4_ISFINITE(_long_control_sp.height_rate) ? NAN : _long_control_sp.altitude; + + tecs_update_pitch_throttle(control_interval, altitude_sp, + airspeed_sp_eas, + _long_configuration.pitch_min, + _long_configuration.pitch_max, + _long_configuration.throttle_min, + _long_configuration.throttle_max, + _long_configuration.sink_rate_target, + _long_configuration.climb_rate_target, + _long_configuration.disable_underspeed_protection, + _long_control_sp.height_rate + ); + + pitch_sp = PX4_ISFINITE(_long_control_sp.pitch_direct) ? _long_control_sp.pitch_direct : _tecs.get_pitch_setpoint(); + throttle_sp = PX4_ISFINITE(_long_control_sp.throttle_direct) ? _long_control_sp.throttle_direct : + _tecs.get_throttle_setpoint(); + + // ----- Lateral ------ + float roll_sp {NAN}; + + if (_fw_lateral_ctrl_sub.updated()) { + // We store the update of _fw_lateral_ctrl_sub in a member variable instead of only local such that we can run + // the controllers also without new setpoints. + _fw_lateral_ctrl_sub.copy(&_lat_control_sp); + } + + float airspeed_direction_sp{NAN}; + float lateral_accel_sp {NAN}; + const Vector2f airspeed_vector = _lateral_control_state.ground_speed - _lateral_control_state.wind_speed; + + if (PX4_ISFINITE(_lat_control_sp.course) && !PX4_ISFINITE(_lat_control_sp.airspeed_direction)) { + // only use the course setpoint if it's finite but airspeed_direction is not + + airspeed_direction_sp = _course_to_airspeed.mapCourseSetpointToHeadingSetpoint( + _lat_control_sp.course, _lateral_control_state.wind_speed, + airspeed_sp_eas); + + // Note: the here updated _min_airspeed_from_guidance is only used in the next iteration + // in the longitudinal controller. + const float max_true_airspeed = _performance_model.getMaximumCalibratedAirspeed() * _long_control_state.eas2tas; + _min_airspeed_from_guidance = _course_to_airspeed.getMinAirspeedForCurrentBearing( + _lat_control_sp.course, _lateral_control_state.wind_speed, + max_true_airspeed, _param_fw_gnd_spd_min.get()) + / _long_control_state.eas2tas; + + } else if (PX4_ISFINITE(_lat_control_sp.airspeed_direction)) { + // If the airspeed_direction is finite we use that instead of the course. + + airspeed_direction_sp = _lat_control_sp.airspeed_direction; + _min_airspeed_from_guidance = 0.f; // reset if no longer in course control + + } else { + _min_airspeed_from_guidance = 0.f; // reset if no longer in course control + } + + if (PX4_ISFINITE(airspeed_direction_sp)) { + const float heading = atan2f(airspeed_vector(1), airspeed_vector(0)); + lateral_accel_sp = _airspeed_direction_control.controlHeading(airspeed_direction_sp, heading, + airspeed_vector.norm()); + } + + if (PX4_ISFINITE(_lat_control_sp.lateral_acceleration)) { + lateral_accel_sp = PX4_ISFINITE(lateral_accel_sp) ? lateral_accel_sp + _lat_control_sp.lateral_acceleration : + _lat_control_sp.lateral_acceleration; + } + + if (!PX4_ISFINITE(lateral_accel_sp)) { + lateral_accel_sp = 0.f; // mitigation if no valid setpoint is received: 0 lateral acceleration + } + + lateral_accel_sp = getCorrectedLateralAccelSetpoint(lateral_accel_sp); + lateral_accel_sp = math::constrain(lateral_accel_sp, -_lateral_configuration.lateral_accel_max, + _lateral_configuration.lateral_accel_max); + roll_sp = mapLateralAccelerationToRollAngle(lateral_accel_sp); + + fixed_wing_lateral_status_s fixed_wing_lateral_status{}; + fixed_wing_lateral_status.timestamp = hrt_absolute_time(); + fixed_wing_lateral_status.lateral_acceleration = lateral_accel_sp; + fixed_wing_lateral_status.can_run_factor = _can_run_factor; + + _fixed_wing_lateral_status_pub.publish(fixed_wing_lateral_status); + + // additional is_finite checks that should not be necessary, but are kept for safety + float roll_body = PX4_ISFINITE(roll_sp) ? roll_sp : 0.0f; + float pitch_body = PX4_ISFINITE(pitch_sp) ? pitch_sp : 0.0f; + const float yaw_body = _yaw; // yaw is not controlled in fixed wing, need to set it though for quaternion generation + const float thrust_body_x = PX4_ISFINITE(throttle_sp) ? throttle_sp : 0.0f; + + if (_control_mode_sub.get().flag_control_manual_enabled) { + roll_body = constrain(roll_body, -radians(_param_fw_r_lim.get()), + radians(_param_fw_r_lim.get())); + pitch_body = constrain(pitch_body, radians(_param_fw_p_lim_min.get()), + radians(_param_fw_p_lim_max.get())); + } + + // roll slew rate + roll_body = _roll_slew_rate.update(roll_body, control_interval); + + _att_sp.timestamp = hrt_absolute_time(); + const Quatf q(Eulerf(roll_body, pitch_body, yaw_body)); + q.copyTo(_att_sp.q_d); + + _att_sp.thrust_body[0] = thrust_body_x; + + _attitude_sp_pub.publish(_att_sp); + + } + + _z_reset_counter = _local_pos.z_reset_counter; + } + + perf_end(_loop_perf); +} + +void FwLateralLongitudinalControl::updateControllerConfiguration() +{ + if (_lateral_configuration.timestamp == 0) { + _lateral_configuration.timestamp = _local_pos.timestamp; + _lateral_configuration.lateral_accel_max = tanf(radians(_param_fw_r_lim.get())) * CONSTANTS_ONE_G; + + } + + if (_long_configuration.timestamp == 0) { + setDefaultLongitudinalControlConfiguration(); + } + + if (_long_control_configuration_sub.updated() || _parameter_update_sub.updated()) { + longitudinal_control_configuration_s configuration_in{}; + _long_control_configuration_sub.copy(&configuration_in); + updateLongitudinalControlConfiguration(configuration_in); + } + + if (_lateral_control_configuration_sub.updated() || _parameter_update_sub.updated()) { + lateral_control_configuration_s configuration_in{}; + _lateral_control_configuration_sub.copy(&configuration_in); + _lateral_configuration.timestamp = configuration_in.timestamp; + + if (PX4_ISFINITE(configuration_in.lateral_accel_max)) { + _lateral_configuration.lateral_accel_max = min(configuration_in.lateral_accel_max, tanf(radians( + _param_fw_r_lim.get())) * CONSTANTS_ONE_G); + + } else { + _lateral_configuration.lateral_accel_max = tanf(radians(_param_fw_r_lim.get())) * CONSTANTS_ONE_G; + } + } +} + +void +FwLateralLongitudinalControl::tecs_update_pitch_throttle(const float control_interval, float alt_sp, float airspeed_sp, + float pitch_min_rad, float pitch_max_rad, float throttle_min, + float throttle_max, const float desired_max_sinkrate, + const float desired_max_climbrate, + bool disable_underspeed_detection, float hgt_rate_sp) +{ + bool tecs_is_running = true; + + // do not run TECS if vehicle is a VTOL and we are in rotary wing mode or in transition + if (_vehicle_status_sub.get().is_vtol + && (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING + || _vehicle_status_sub.get().in_transition_mode)) { + tecs_is_running = false; + return; + + } + + const float throttle_trim_compensated = _performance_model.getTrimThrottle(throttle_min, + throttle_max, airspeed_sp, _air_density); + + _tecs.set_detect_underspeed_enabled(!disable_underspeed_detection); + + // HOTFIX: the airspeed rate estimate using acceleration in body-forward direction has shown to lead to high biases + // when flying tight turns. It's in this case much safer to just set the estimated airspeed rate to 0. + const float airspeed_rate_estimate = 0.f; + + _tecs.update(_long_control_state.pitch_rad - radians(_param_fw_psp_off.get()), + _long_control_state.altitude_msl, + alt_sp, + airspeed_sp, + _long_control_state.airspeed_eas, + _long_control_state.eas2tas, + throttle_min, + throttle_max, + throttle_trim_compensated, + pitch_min_rad - radians(_param_fw_psp_off.get()), + pitch_max_rad - radians(_param_fw_psp_off.get()), + desired_max_climbrate, + desired_max_sinkrate, + airspeed_rate_estimate, + _long_control_state.height_rate, + hgt_rate_sp); + + tecs_status_publish(alt_sp, airspeed_sp, airspeed_rate_estimate, throttle_trim_compensated); + + if (tecs_is_running && !_vehicle_status_sub.get().in_transition_mode + && (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING)) { + const TECS::DebugOutput &tecs_output{_tecs.getStatus()}; + + // Check level flight: the height rate setpoint is not set or set to 0 and we are close to the target altitude and target altitude is not moving + if ((fabsf(tecs_output.height_rate_reference) < MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT) && + fabsf(_long_control_state.altitude_msl - tecs_output.altitude_reference) < _param_nav_fw_alt_rad.get()) { + _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_LEVEL; + + } else if (((tecs_output.altitude_reference - _long_control_state.altitude_msl) >= _param_nav_fw_alt_rad.get()) || + (tecs_output.height_rate_reference >= MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT)) { + _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_CLIMB; + + } else if (((_long_control_state.altitude_msl - tecs_output.altitude_reference) >= _param_nav_fw_alt_rad.get()) || + (tecs_output.height_rate_reference <= -MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT)) { + _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_DESCEND; + + } else { + //We can't infer the flight phase , do nothing, estimation is reset at each step + } + } +} + +void +FwLateralLongitudinalControl::tecs_status_publish(float alt_sp, float equivalent_airspeed_sp, + float true_airspeed_derivative_raw, float throttle_trim) +{ + tecs_status_s tecs_status{}; + + const TECS::DebugOutput &debug_output{_tecs.getStatus()}; + + tecs_status.altitude_sp = alt_sp; + tecs_status.altitude_reference = debug_output.altitude_reference; + tecs_status.altitude_time_constant = _tecs.get_altitude_error_time_constant(); + tecs_status.height_rate_reference = debug_output.height_rate_reference; + tecs_status.height_rate_direct = debug_output.height_rate_direct; + tecs_status.height_rate_setpoint = debug_output.control.altitude_rate_control; + tecs_status.height_rate = -_local_pos.vz; + tecs_status.equivalent_airspeed_sp = equivalent_airspeed_sp; + tecs_status.true_airspeed_sp = debug_output.true_airspeed_sp; + tecs_status.true_airspeed_filtered = debug_output.true_airspeed_filtered; + tecs_status.true_airspeed_derivative_sp = debug_output.control.true_airspeed_derivative_control; + tecs_status.true_airspeed_derivative = debug_output.true_airspeed_derivative; + tecs_status.true_airspeed_derivative_raw = true_airspeed_derivative_raw; + tecs_status.total_energy_rate = debug_output.control.total_energy_rate_estimate; + tecs_status.total_energy_balance_rate = debug_output.control.energy_balance_rate_estimate; + tecs_status.total_energy_rate_sp = debug_output.control.total_energy_rate_sp; + tecs_status.total_energy_balance_rate_sp = debug_output.control.energy_balance_rate_sp; + tecs_status.throttle_integ = debug_output.control.throttle_integrator; + tecs_status.pitch_integ = debug_output.control.pitch_integrator; + tecs_status.throttle_sp = _tecs.get_throttle_setpoint(); + tecs_status.pitch_sp_rad = _tecs.get_pitch_setpoint(); + tecs_status.throttle_trim = throttle_trim; + tecs_status.underspeed_ratio = _tecs.get_underspeed_ratio(); + tecs_status.fast_descend_ratio = debug_output.fast_descend; + + tecs_status.timestamp = hrt_absolute_time(); + + _tecs_status_pub.publish(tecs_status); +} + +int FwLateralLongitudinalControl::task_spawn(int argc, char *argv[]) +{ + bool is_vtol = false; + + if (argc > 1) { + if (strcmp(argv[1], "vtol") == 0) { + is_vtol = true; + } + } + + FwLateralLongitudinalControl *instance = new FwLateralLongitudinalControl(is_vtol); + + if (instance) { + _object.store(instance); + _task_id = task_id_is_work_queue; + + if (instance->init()) { + return PX4_OK; + } + + } else { + PX4_ERR("alloc failed"); + } + + delete instance; + _object.store(nullptr); + _task_id = -1; + + return PX4_ERROR; +} + +bool +FwLateralLongitudinalControl::init() +{ + if (!_local_pos_sub.registerCallback()) { + PX4_ERR("callback registration failed"); + return false; + } + + return true; +} + +int FwLateralLongitudinalControl::custom_command(int argc, char *argv[]) +{ + return print_usage("unknown command"); +} + +int FwLateralLongitudinalControl::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +fw_lat_lon_control computes attitude and throttle setpoints from lateral and longitudinal control setpoints. + +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("fw_lat_lon_control", "controller"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_ARG("vtol", "VTOL mode", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +void FwLateralLongitudinalControl::update_control_state() { + updateAltitudeAndHeightRate(); + updateAirspeed(); + updateAttitude(); + updateWind(); + + _lateral_control_state.ground_speed = Vector2f(_local_pos.vx, _local_pos.vy); +} + +void FwLateralLongitudinalControl::updateWind() { + if (_wind_sub.updated()) { + wind_s wind{}; + _wind_sub.update(&wind); + + // assumes wind is valid if finite + _wind_valid = PX4_ISFINITE(wind.windspeed_north) + && PX4_ISFINITE(wind.windspeed_east); + + _time_wind_last_received = hrt_absolute_time(); + + _lateral_control_state.wind_speed(0) = wind.windspeed_north; + _lateral_control_state.wind_speed(1) = wind.windspeed_east; + + } else { + // invalidate wind estimate usage (and correspondingly NPFG, if enabled) after subscription timeout + _wind_valid = _wind_valid && (hrt_absolute_time() - _time_wind_last_received) < WIND_EST_TIMEOUT; + } + + if (!_wind_valid) { + _lateral_control_state.wind_speed.setZero(); + } +} + +void FwLateralLongitudinalControl::updateAltitudeAndHeightRate() { + float ref_alt{0.f}; + if (_local_pos.z_global && PX4_ISFINITE(_local_pos.ref_alt)) { + ref_alt = _local_pos.ref_alt; + } + + _long_control_state.altitude_msl = -_local_pos.z + ref_alt; // Altitude AMSL in meters + _long_control_state.height_rate = -_local_pos.vz; + +} + +void FwLateralLongitudinalControl::updateAttitude() { + vehicle_attitude_s att; + + if (_vehicle_attitude_sub.update(&att)) { + + Dcmf R{Quatf(att.q)}; + + // if the vehicle is a tailsitter we have to rotate the attitude by the pitch offset + // between multirotor and fixed wing flight + if (_vehicle_status_sub.get().is_vtol_tailsitter) { + const Dcmf R_offset{Eulerf{0.f, M_PI_2_F, 0.f}}; + R = R * R_offset; + } + + const Eulerf euler_angles(R); + _long_control_state.pitch_rad = euler_angles.theta(); + _yaw = euler_angles.psi(); + + // load factor due to banking + const float load_factor_from_bank_angle = 1.0f / max(cosf(euler_angles.phi()), FLT_EPSILON); + _tecs.set_load_factor(load_factor_from_bank_angle); + } +} + +void FwLateralLongitudinalControl::updateAirspeed() { + + airspeed_validated_s airspeed_validated; + + if (_param_fw_use_airspd.get() && _airspeed_validated_sub.update(&airspeed_validated)) { + + // do not use synthetic airspeed as this would create a thrust loop + if (PX4_ISFINITE(airspeed_validated.calibrated_airspeed_m_s) + && PX4_ISFINITE(airspeed_validated.true_airspeed_m_s) + && airspeed_validated.airspeed_source != airspeed_validated_s::SYNTHETIC) { + + _time_airspeed_last_valid = airspeed_validated.timestamp; + _long_control_state.airspeed_eas = airspeed_validated.calibrated_airspeed_m_s; + _long_control_state.eas2tas = constrain(airspeed_validated.true_airspeed_m_s / airspeed_validated.calibrated_airspeed_m_s, 0.9f, 2.0f); + } + } + + // no airspeed updates for one second --> declare invalid + const bool airspeed_valid = hrt_elapsed_time(&_time_airspeed_last_valid) < 1_s; + + if (!airspeed_valid) { + _long_control_state.eas2tas = 1.f; + } + + _tecs.enable_airspeed(airspeed_valid); +} + +float +FwLateralLongitudinalControl::adapt_airspeed_setpoint(const float control_interval, float calibrated_airspeed_setpoint, + float calibrated_min_airspeed_guidance, float wind_speed) +{ + float system_min_airspeed = _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); + + const float system_max_airspeed = _performance_model.getMaximumCalibratedAirspeed(); + + // airspeed setpoint adjustments + if (!PX4_ISFINITE(calibrated_airspeed_setpoint) || calibrated_airspeed_setpoint <= FLT_EPSILON) { + calibrated_airspeed_setpoint = _performance_model.getCalibratedTrimAirspeed(); + + // Aditional option to increase the min airspeed setpoint based on wind estimate for more stability in higher winds. + if (_wind_valid && _param_fw_wind_arsp_sc.get() > FLT_EPSILON) { + system_min_airspeed = math::min(system_min_airspeed + _param_fw_wind_arsp_sc.get() * + wind_speed, system_max_airspeed); + } + } + + // increase setpoint to at what's at least required for the lateral guidance + calibrated_airspeed_setpoint = math::max(calibrated_airspeed_setpoint, calibrated_min_airspeed_guidance); + + // constrain airspeed to feasible range + calibrated_airspeed_setpoint = math::constrain(calibrated_airspeed_setpoint, system_min_airspeed, system_max_airspeed); + + if (!PX4_ISFINITE(_airspeed_slew_rate_controller.getState())) { + + // initialize the airspeed setpoint + if (PX4_ISFINITE(_long_control_state.airspeed_eas) && _long_control_state.airspeed_eas < system_min_airspeed) { + // current airpseed is below minimum - init with minimum + _airspeed_slew_rate_controller.setForcedValue(system_min_airspeed); + + } else if (PX4_ISFINITE(_long_control_state.airspeed_eas) && _long_control_state.airspeed_eas > system_max_airspeed) { + // current airpseed is above maximum - init with maximum + _airspeed_slew_rate_controller.setForcedValue(system_max_airspeed); + + } else if (PX4_ISFINITE(_long_control_state.airspeed_eas)) { + // current airpseed is between min and max - init with current + _airspeed_slew_rate_controller.setForcedValue(_long_control_state.airspeed_eas); + + } else { + // current airpseed is invalid - init with setpoint + _airspeed_slew_rate_controller.setForcedValue(calibrated_airspeed_setpoint); + } + } else { + // update slew rate state + if (_airspeed_slew_rate_controller.getState() < system_min_airspeed) { + // current airpseed setpoint is below minimum - reset to minimum + _airspeed_slew_rate_controller.setForcedValue(system_min_airspeed); + + } else if (_airspeed_slew_rate_controller.getState() > system_max_airspeed) { + // current airpseed setpoint is above maximum - reset to maximum + _airspeed_slew_rate_controller.setForcedValue(system_max_airspeed); + + } else if (PX4_ISFINITE(_long_control_state.airspeed_eas)) { + // current airpseed setpoint is between min and max - update + _airspeed_slew_rate_controller.update(calibrated_airspeed_setpoint, control_interval); + + } + } + + return _airspeed_slew_rate_controller.getState(); +} + +bool FwLateralLongitudinalControl::checkLowHeightConditions() const +{ + // Are conditions for low-height + return _param_fw_t_thr_low_hgt.get() >= 0.f && _local_pos.dist_bottom_valid + && _local_pos.dist_bottom < _param_fw_t_thr_low_hgt.get(); +} + +void FwLateralLongitudinalControl::updateTECSAltitudeTimeConstant(const bool is_low_height, const float dt) +{ + // Target time constant for the TECS altitude tracker + float alt_tracking_tc = _param_fw_t_h_error_tc.get(); + + if (is_low_height) { + // If low-height conditions satisfied, compute target time constant for altitude tracking + alt_tracking_tc *= _param_fw_thrtc_sc.get(); + } + + _tecs_alt_time_const_slew_rate.update(alt_tracking_tc, dt); +} + +float FwLateralLongitudinalControl::getGuidanceQualityFactor(const vehicle_local_position_s &local_pos, const bool is_wind_valid) const +{ + if (is_wind_valid) { + // If we have a valid wind estimate, npfg is able to handle all degenerated cases + return 1.f; + } + + // NPFG can run without wind information as long as the system is not flying backwards and has a minimal ground speed + // Check the minimal ground speed. if it is greater than twice the standard deviation, we assume that we can infer a valid track angle + const Vector2f ground_vel(local_pos.vx, local_pos.vy); + const float ground_speed(ground_vel.norm()); + const float low_ground_speed_factor(math::constrain((ground_speed - HORIZONTAL_EVH_FACTOR_COURSE_INVALID * + local_pos.evh) / ((HORIZONTAL_EVH_FACTOR_COURSE_VALID - HORIZONTAL_EVH_FACTOR_COURSE_INVALID)*local_pos.evh), + 0.f, 1.f)); + + // Check that the angle between heading and track is not off too much. if it is greater than 90° we will be pushed back from the wind and the npfg will propably give a roll command in the wrong direction. + const Vector2f heading_vector(matrix::Dcm2f(local_pos.heading)*Vector2f({1.f, 0.f})); + const Vector2f ground_vel_norm(ground_vel.normalized()); + const float flying_forward_factor(math::constrain((heading_vector.dot(ground_vel_norm) - + COS_HEADING_TRACK_ANGLE_PUSHED_BACK) / ((COS_HEADING_TRACK_ANGLE_NOT_PUSHED_BACK - + COS_HEADING_TRACK_ANGLE_PUSHED_BACK)), + 0.f, 1.f)); + + return flying_forward_factor * low_ground_speed_factor; +} +float FwLateralLongitudinalControl::getCorrectedLateralAccelSetpoint(float lateral_accel_sp) +{ + // Scale the npfg output to zero if npfg is not certain for correct output + _can_run_factor = math::constrain(getGuidanceQualityFactor(_local_pos, _wind_valid), 0.f, 1.f); + + hrt_abstime now{hrt_absolute_time()}; + + // Warn the user when the scale is less than 90% for at least 2 seconds (disable in transition) + + // If the npfg was not running before, reset the user warning variables. + if ((now - _time_since_last_npfg_call) > ROLL_WARNING_TIMEOUT) { + _need_report_npfg_uncertain_condition = true; + _time_since_first_reduced_roll = 0U; + } + + if (_vehicle_status_sub.get().in_transition_mode || _can_run_factor > ROLL_WARNING_CAN_RUN_THRESHOLD || _landed) { + // NPFG reports a good condition or we are in transition, reset the user warning variables. + _need_report_npfg_uncertain_condition = true; + _time_since_first_reduced_roll = 0U; + + } else if (_need_report_npfg_uncertain_condition) { + if (_time_since_first_reduced_roll == 0U) { + _time_since_first_reduced_roll = now; + } + + if ((now - _time_since_first_reduced_roll) > ROLL_WARNING_TIMEOUT) { + _need_report_npfg_uncertain_condition = false; + events::send(events::ID("npfg_roll_command_uncertain"), events::Log::Warning, + "Roll command reduced due to uncertain velocity/wind estimates!"); + } + + } else { + // Nothing to do, already reported. + } + + _time_since_last_npfg_call = now; + + return _can_run_factor * (lateral_accel_sp); +} +float FwLateralLongitudinalControl::mapLateralAccelerationToRollAngle(float lateral_acceleration_sp) const { + return atanf(lateral_acceleration_sp / CONSTANTS_ONE_G); +} + +void FwLateralLongitudinalControl::setDefaultLongitudinalControlConfiguration() { + _long_configuration.timestamp = hrt_absolute_time(); + _long_configuration.pitch_min = radians(_param_fw_p_lim_min.get()); + _long_configuration.pitch_max = radians(_param_fw_p_lim_max.get()); + _long_configuration.throttle_min = _param_fw_thr_min.get(); + _long_configuration.throttle_max = _param_fw_thr_max.get(); + _long_configuration.climb_rate_target = _param_climbrate_target.get(); + _long_configuration.sink_rate_target = _param_sinkrate_target.get(); + _long_configuration.disable_underspeed_protection = false; + _long_configuration.enforce_low_height_condition = false; +} + +void FwLateralLongitudinalControl::updateLongitudinalControlConfiguration(const longitudinal_control_configuration_s &configuration_in) { + _long_configuration.timestamp = configuration_in.timestamp; + + if (PX4_ISFINITE(configuration_in.pitch_min)) { + _long_configuration.pitch_min = math::constrain(configuration_in.pitch_min, radians(_param_fw_p_lim_min.get()), radians(_param_fw_p_lim_max.get())); + } else { + _long_configuration.pitch_min = radians(_param_fw_p_lim_min.get()); + } + + if (PX4_ISFINITE(configuration_in.pitch_max)) { + _long_configuration.pitch_max = math::constrain(configuration_in.pitch_max, _long_configuration.pitch_min, radians(_param_fw_p_lim_max.get())); + } else { + _long_configuration.pitch_max = radians(_param_fw_p_lim_max.get()); + } + + if (PX4_ISFINITE(configuration_in.throttle_min)) { + _long_configuration.throttle_min = math::constrain(configuration_in.throttle_min, _param_fw_thr_min.get(), _param_fw_thr_max.get()); + } else { + _long_configuration.throttle_min = _param_fw_thr_min.get(); + } + + if (PX4_ISFINITE(configuration_in.throttle_max)) { + _long_configuration.throttle_max = math::constrain(configuration_in.throttle_max, _long_configuration.throttle_min, _param_fw_thr_max.get()); + } else { + _long_configuration.throttle_max = _param_fw_thr_max.get(); + } + + if (PX4_ISFINITE(configuration_in.climb_rate_target)) { + _long_configuration.climb_rate_target = math::max(0.0f, configuration_in.climb_rate_target); + } else { + _long_configuration.climb_rate_target = _param_climbrate_target.get(); + } + + if (PX4_ISFINITE(configuration_in.sink_rate_target)) { + _long_configuration.sink_rate_target = math::max(0.0f, configuration_in.sink_rate_target); + } else { + _long_configuration.sink_rate_target = _param_sinkrate_target.get(); + } +} + +float FwLateralLongitudinalControl::getLoadFactor() const +{ + float load_factor_from_bank_angle = 1.f; + + const float roll_body = Eulerf(Quatf(_att_sp.q_d)).phi(); + + if (PX4_ISFINITE(roll_body)) { + load_factor_from_bank_angle = 1.f / math::max(cosf(roll_body), FLT_EPSILON); + } + + return load_factor_from_bank_angle; +} + +extern "C" __EXPORT int fw_lat_lon_control_main(int argc, char *argv[]) +{ + return FwLateralLongitudinalControl::main(argc, argv); +} diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp new file mode 100644 index 0000000000..703fb722e9 --- /dev/null +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp @@ -0,0 +1,260 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + +/** + * @file FwLateralLongitudinalControl.hpp + */ + +#ifndef PX4_FWLATERALLONGITUDINALCONTROL_HPP +#define PX4_FWLATERALLONGITUDINALCONTROL_HPP + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static constexpr fixed_wing_lateral_setpoint_s empty_lateral_control_setpoint = {.timestamp = 0, .course = NAN, .airspeed_direction = NAN, .lateral_acceleration = NAN}; +static constexpr fixed_wing_longitudinal_setpoint_s empty_longitudinal_control_setpoint = {.timestamp = 0, .altitude = NAN, .height_rate = NAN, .equivalent_airspeed = NAN, .pitch_direct = NAN, .throttle_direct = NAN}; + +class FwLateralLongitudinalControl final : public ModuleBase, public ModuleParams, + public px4::WorkItem +{ +public: + FwLateralLongitudinalControl(bool is_vtol); + + ~FwLateralLongitudinalControl() override; + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + bool init(); + +private: + void Run() override; + + uORB::SubscriptionCallbackWorkItem _local_pos_sub{this, ORB_ID(vehicle_local_position)}; + + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + + uORB::Subscription _airspeed_validated_sub{ORB_ID(airspeed_validated)}; + uORB::Subscription _wind_sub{ORB_ID(wind)}; + uORB::SubscriptionData _control_mode_sub{ORB_ID(vehicle_control_mode)}; + uORB::SubscriptionData _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _vehicle_landed_sub{ORB_ID(vehicle_land_detected)}; + uORB::SubscriptionData _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::Subscription _fw_lateral_ctrl_sub{ORB_ID(fixed_wing_lateral_setpoint)}; + uORB::Subscription _fw_longitudinal_ctrl_sub{ORB_ID(fixed_wing_longitudinal_setpoint)}; + uORB::Subscription _long_control_configuration_sub{ORB_ID(longitudinal_control_configuration)}; + uORB::Subscription _lateral_control_configuration_sub{ORB_ID(lateral_control_configuration)}; + + vehicle_local_position_s _local_pos{}; + fixed_wing_longitudinal_setpoint_s _long_control_sp{empty_longitudinal_control_setpoint}; + longitudinal_control_configuration_s _long_configuration{}; + fixed_wing_lateral_setpoint_s _lat_control_sp{empty_lateral_control_setpoint}; + lateral_control_configuration_s _lateral_configuration{}; + + uORB::Publication _attitude_sp_pub; + uORB::Publication _tecs_status_pub{ORB_ID(tecs_status)}; + uORB::PublicationData _flight_phase_estimation_pub{ORB_ID(flight_phase_estimation)}; + uORB::Publication _fixed_wing_lateral_status_pub{ORB_ID(fixed_wing_lateral_status)}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_fw_psp_off, + (ParamBool) _param_fw_use_airspd, + (ParamFloat) _param_nav_fw_alt_rad, + (ParamFloat) _param_fw_r_lim, + (ParamFloat) _param_fw_p_lim_max, + (ParamFloat) _param_fw_p_lim_min, + (ParamFloat) _param_fw_pn_r_slew_max, + (ParamFloat) _param_fw_t_hrate_ff, + (ParamFloat) _param_fw_t_h_error_tc, + (ParamFloat) _param_fw_t_fast_alt_err, + (ParamFloat) _param_fw_t_thr_integ, + (ParamFloat) _param_fw_t_I_gain_pit, + (ParamFloat) _param_fw_t_ptch_damp, + (ParamFloat) _param_fw_t_rll2thr, + (ParamFloat) _param_fw_t_sink_max, + (ParamFloat) _param_fw_t_tas_error_tc, + (ParamFloat) _param_fw_t_thr_damping, + (ParamFloat) _param_fw_t_vert_acc, + (ParamFloat) _param_ste_rate_time_const, + (ParamFloat) _param_seb_rate_ff, + (ParamFloat) _param_speed_standard_dev, + (ParamFloat) _param_speed_rate_standard_dev, + (ParamFloat) _param_process_noise_standard_dev, + (ParamFloat) _param_climbrate_target, + (ParamFloat) _param_sinkrate_target, + (ParamFloat) _param_fw_thr_max, + (ParamFloat) _param_fw_thr_min, + (ParamFloat) _param_fw_thr_slew_max, + (ParamFloat) _param_fw_thrtc_sc, + (ParamFloat) _param_fw_t_thr_low_hgt, + (ParamFloat) _param_fw_wind_arsp_sc, + (ParamFloat) _param_fw_gnd_spd_min + ) + + hrt_abstime _last_time_loop_ran{}; + uint8_t _z_reset_counter{UINT8_C(0)}; + uint64_t _time_airspeed_last_valid{UINT64_C(0)}; + float _air_density{atmosphere::kAirDensitySeaLevelStandardAtmos}; + // Smooths changes in the altitude tracking error time constant value + SlewRate _tecs_alt_time_const_slew_rate; + struct longitudinal_control_state { + float pitch_rad{0.f}; + float altitude_msl{0.f}; + float airspeed_eas{0.f}; + float eas2tas{1.f}; + float height_rate{0.f}; + } _long_control_state{}; + + bool _wind_valid{false}; + hrt_abstime _time_wind_last_received{0}; + SlewRate _roll_slew_rate; + float _yaw{0.f}; + struct lateral_control_state { + matrix::Vector2f ground_speed; + matrix::Vector2f wind_speed; + } _lateral_control_state{}; + bool _need_report_npfg_uncertain_condition{false}; ///< boolean if reporting of uncertain npfg output condition is needed + hrt_abstime _time_since_first_reduced_roll{0U}; ///< absolute time since start when entering reduced roll angle for the first time + hrt_abstime _time_since_last_npfg_call{0U}; ///< absolute time since start when the npfg reduced roll angle calculations was last performed + vehicle_attitude_setpoint_s _att_sp{}; + bool _landed{false}; + float _can_run_factor{0.f}; + SlewRate _airspeed_slew_rate_controller; + + perf_counter_t _loop_perf; // loop performance counter + + PerformanceModel _performance_model; + TECS _tecs; + CourseToAirspeedRefMapper _course_to_airspeed; + AirspeedDirectionController _airspeed_direction_control; + + float _min_airspeed_from_guidance{0.f}; // need to store it bc we only update after running longitudinal controller + + void parameters_update(); + void update_control_state(); + void tecs_update_pitch_throttle(const float control_interval, float alt_sp, float airspeed_sp, + float pitch_min_rad, float pitch_max_rad, float throttle_min, + float throttle_max, const float desired_max_sinkrate, + const float desired_max_climbrate, + bool disable_underspeed_detection, float hgt_rate_sp); + + void tecs_status_publish(float alt_sp, float equivalent_airspeed_sp, float true_airspeed_derivative_raw, + float throttle_trim); + + void updateAirspeed(); + + void updateAttitude(); + + void updateAltitudeAndHeightRate(); + + float mapLateralAccelerationToRollAngle(float lateral_acceleration_sp) const; + + void updateWind(); + + void updateTECSAltitudeTimeConstant(const bool is_low_height, const float dt); + + bool checkLowHeightConditions() const; + + float getGuidanceQualityFactor(const vehicle_local_position_s &local_pos, const bool is_wind_valid) const; + + float getCorrectedLateralAccelSetpoint(float lateral_accel_sp); + + void setDefaultLongitudinalControlConfiguration(); + + void updateLongitudinalControlConfiguration(const longitudinal_control_configuration_s &configuration_in); + + void updateControllerConfiguration(); + + float getLoadFactor() const; + + /** + * @brief Returns an adapted calibrated airspeed setpoint + * + * Adjusts the setpoint for wind, accelerated stall, and slew rates. + * + * @param control_interval Time since the last position control update [s] + * @param calibrated_airspeed_setpoint Calibrated airspeed septoint (generally from the position setpoint) [m/s] + * @param calibrated_min_airspeed_guidance Minimum airspeed required for lateral guidance [m/s] + * @return Adjusted calibrated airspeed setpoint [m/s] + */ + float adapt_airspeed_setpoint(const float control_interval, float calibrated_airspeed_setpoint, + float calibrated_min_airspeed_guidance, float wind_speed); +}; + +#endif //PX4_FWLATERALLONGITUDINALCONTROL_HPP diff --git a/src/modules/fw_lateral_longitudinal_control/Kconfig b/src/modules/fw_lateral_longitudinal_control/Kconfig new file mode 100644 index 0000000000..aefa5a7559 --- /dev/null +++ b/src/modules/fw_lateral_longitudinal_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_FW_LATERAL_LONGITUDINAL_CONTROL + bool "fw_lateral_longitudinal_control" + default n + ---help--- + Enable support for fw_lat_lon_control diff --git a/src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c b/src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c new file mode 100644 index 0000000000..130c0a1bd7 --- /dev/null +++ b/src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c @@ -0,0 +1,284 @@ +/** + * Path navigation roll slew rate limit. + * + * Maximum change in roll angle setpoint per second. + * Applied in all Auto modes, plus manual Position & Altitude modes. + * + * @unit deg/s + * @min 0 + * @decimal 0 + * @increment 1 + * @group FW Path Control + */ +PARAM_DEFINE_FLOAT(FW_PN_R_SLEW_MAX, 90.0f); + +/** + * Minimum groundspeed + * + * The controller will increase the commanded airspeed to maintain + * this minimum groundspeed to the next waypoint. + * + * @unit m/s + * @min 0.0 + * @max 40 + * @decimal 1 + * @increment 0.5 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); + + + + +// ----------longitudinal params---------- + +/** + * Throttle max slew rate + * + * Maximum slew rate for the commanded throttle + * + * @min 0.0 + * @max 1.0 + * @decimal 2 + * @increment 0.01 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); + +/** + * Low-height threshold for tighter altitude tracking + * + * Height above ground threshold below which tighter altitude + * tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly + * (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC + * to FW_LND_THRTC_SC*FW_T_ALT_TC. + * + * -1 to disable. + * + * @unit m + * @min -1 + * @decimal 0 + * @increment 1 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_THR_LOW_HGT, -1.f); + +/** + * Throttle damping factor + * + * This is the damping gain for the throttle demand loop. + * + * @min 0.0 + * @max 1.0 + * @decimal 3 + * @increment 0.01 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_THR_DAMPING, 0.05f); + +/** + * Integrator gain throttle + * + * Increase it to trim out speed and height offsets faster, + * with the downside of possible overshoots and oscillations. + * + * @min 0.0 + * @max 1.0 + * @decimal 3 + * @increment 0.005 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_THR_INTEG, 0.02f); + +/** + * Integrator gain pitch + * + * Increase it to trim out speed and height offsets faster, + * with the downside of possible overshoots and oscillations. + * + * @min 0.0 + * @max 2.0 + * @decimal 2 + * @increment 0.05 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f); + +/** + * Maximum vertical acceleration + * + * This is the maximum vertical acceleration + * either up or down that the controller will use to correct speed + * or height errors. + * + * @unit m/s^2 + * @min 1.0 + * @max 10.0 + * @decimal 1 + * @increment 0.5 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); + +/** + * Airspeed measurement standard deviation + * + * For the airspeed filter in TECS. + * + * @unit m/s + * @min 0.01 + * @max 10.0 + * @decimal 2 + * @increment 0.1 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.07f); + +/** + * Airspeed rate measurement standard deviation + * + * For the airspeed filter in TECS. + * + * @unit m/s^2 + * @min 0.01 + * @max 10.0 + * @decimal 2 + * @increment 0.1 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_SPD_DEV_STD, 0.2f); + +/** + * Process noise standard deviation for the airspeed rate + * + * This is defining the noise in the airspeed rate for the constant airspeed rate model + * of the TECS airspeed filter. + * + * @unit m/s^2 + * @min 0.01 + * @max 10.0 + * @decimal 2 + * @increment 0.1 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_SPD_PRC_STD, 0.2f); + +/** + * Roll -> Throttle feedforward + * + * Is used to compensate for the additional drag created by turning. + * Increase this gain if the aircraft initially loses energy in turns + * and reduce if the aircraft initially gains energy in turns. + * + * @min 0.0 + * @max 20.0 + * @decimal 1 + * @increment 0.5 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); + +/** + * Pitch damping gain + * + * @min 0.0 + * @max 2.0 + * @decimal 2 + * @increment 0.1 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f); + +/** + * Altitude error time constant. + * + * @min 2.0 + * @decimal 2 + * @increment 0.5 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f); + +/** + * Fast descend: minimum altitude error + * + * Minimum altitude error needed to descend with max airspeed and minimal throttle. + * A negative value disables fast descend. + * + * @min -1.0 + * @decimal 0 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_F_ALT_ERR, -1.0f); + +/** + * Height rate feed forward + * + * @min 0.0 + * @max 1.0 + * @decimal 2 + * @increment 0.05 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.3f); + +/** + * True airspeed error time constant. + * + * @min 2.0 + * @decimal 2 + * @increment 0.5 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f); + +/** + * Specific total energy rate first order filter time constant. + * + * This filter is applied to the specific total energy rate used for throttle damping. + * + * @min 0.0 + * @max 2 + * @decimal 2 + * @increment 0.01 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_STE_R_TC, 0.4f); + +/** + * Specific total energy balance rate feedforward gain. + * + * + * @min 0.5 + * @max 3 + * @decimal 2 + * @increment 0.01 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f); + +/** + * Wind-based airspeed scaling factor + * + * Multiplying this factor with the current absolute wind estimate gives the airspeed offset + * added to the minimum airspeed setpoint limit. This helps to make the + * system more robust against disturbances (turbulence) in high wind. + * + * @min 0 + * @decimal 2 + * @increment 0.01 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_WIND_ARSP_SC, 0.f); + +/** + * Maximum descent rate + * + * @unit m/s + * @min 1.0 + * @max 15.0 + * @decimal 1 + * @increment 0.5 + * @group FW TECS + */ +PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); diff --git a/src/modules/fw_pos_control/CMakeLists.txt b/src/modules/fw_pos_control/CMakeLists.txt index 9248e8d2df..163cf17e67 100644 --- a/src/modules/fw_pos_control/CMakeLists.txt +++ b/src/modules/fw_pos_control/CMakeLists.txt @@ -60,6 +60,8 @@ px4_add_module( SRCS FixedwingPositionControl.cpp FixedwingPositionControl.hpp + ControllerConfigurationHandler.cpp + ControllerConfigurationHandler.hpp DEPENDS ${POSCONTROL_DEPENDENCIES} ) diff --git a/src/modules/fw_pos_control/ControllerConfigurationHandler.cpp b/src/modules/fw_pos_control/ControllerConfigurationHandler.cpp new file mode 100644 index 0000000000..fcfabb1679 --- /dev/null +++ b/src/modules/fw_pos_control/ControllerConfigurationHandler.cpp @@ -0,0 +1,139 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + +/** + * @file CombinedControllerConfigurationHandler.cpp + */ + +#include "ControllerConfigurationHandler.hpp" +#include + +using namespace time_literals; + + +void CombinedControllerConfigurationHandler::update(const hrt_abstime now) +{ + _longitudinal_updated = floatValueChanged(_longitudinal_configuration_current_cycle.pitch_min, + _longitudinal_publisher.get().pitch_min); + _longitudinal_updated |= floatValueChanged(_longitudinal_configuration_current_cycle.pitch_max, + _longitudinal_publisher.get().pitch_max); + _longitudinal_updated |= floatValueChanged(_longitudinal_configuration_current_cycle.throttle_min, + _longitudinal_publisher.get().throttle_min); + _longitudinal_updated |= floatValueChanged(_longitudinal_configuration_current_cycle.throttle_max, + _longitudinal_publisher.get().throttle_max); + _longitudinal_updated |= floatValueChanged(_longitudinal_configuration_current_cycle.speed_weight, + _longitudinal_publisher.get().speed_weight); + _longitudinal_updated |= floatValueChanged(_longitudinal_configuration_current_cycle.climb_rate_target, + _longitudinal_publisher.get().climb_rate_target); + _longitudinal_updated |= floatValueChanged(_longitudinal_configuration_current_cycle.sink_rate_target, + _longitudinal_publisher.get().sink_rate_target); + _longitudinal_updated |= booleanValueChanged(_longitudinal_configuration_current_cycle.enforce_low_height_condition, + _longitudinal_publisher.get().enforce_low_height_condition); + _longitudinal_updated |= booleanValueChanged(_longitudinal_configuration_current_cycle.disable_underspeed_protection, + _longitudinal_publisher.get().disable_underspeed_protection); + + _lateral_updated |= floatValueChanged(_lateral_configuration_current_cycle.lateral_accel_max, + _lateral_publisher.get().lateral_accel_max); + + if (_longitudinal_updated || now - _time_last_longitudinal_publish > 1_s) { + _longitudinal_configuration_current_cycle.timestamp = now; + _longitudinal_publisher.update(_longitudinal_configuration_current_cycle); + _time_last_longitudinal_publish = _longitudinal_configuration_current_cycle.timestamp; + } + + if (_lateral_updated || now - _time_last_lateral_publish > 1_s) { + _lateral_configuration_current_cycle.timestamp = now; + _lateral_publisher.update(_lateral_configuration_current_cycle); + _time_last_lateral_publish = _lateral_configuration_current_cycle.timestamp; + } + + _longitudinal_updated = _lateral_updated = false; + _longitudinal_configuration_current_cycle = empty_longitudinal_control_configuration; + _lateral_configuration_current_cycle = empty_lateral_control_configuration; +} + +void CombinedControllerConfigurationHandler::setThrottleMax(float throttle_max) +{ + _longitudinal_configuration_current_cycle.throttle_max = throttle_max; +} + +void CombinedControllerConfigurationHandler::setThrottleMin(float throttle_min) +{ + _longitudinal_configuration_current_cycle.throttle_min = throttle_min; +} + +void CombinedControllerConfigurationHandler::setSpeedWeight(float speed_weight) +{ + _longitudinal_configuration_current_cycle.speed_weight = speed_weight; +} + +void CombinedControllerConfigurationHandler::setPitchMin(const float pitch_min) +{ + _longitudinal_configuration_current_cycle.pitch_min = pitch_min; +} + +void CombinedControllerConfigurationHandler::setPitchMax(const float pitch_max) +{ + _longitudinal_configuration_current_cycle.pitch_max = pitch_max; +} + +void CombinedControllerConfigurationHandler::setClimbRateTarget(float climbrate_target) +{ + _longitudinal_configuration_current_cycle.climb_rate_target = climbrate_target; +} + +void CombinedControllerConfigurationHandler::setDisableUnderspeedProtection(bool disable) +{ + _longitudinal_configuration_current_cycle.disable_underspeed_protection = disable; +} + +void CombinedControllerConfigurationHandler::setSinkRateTarget(const float sinkrate_target) +{ + _longitudinal_configuration_current_cycle.sink_rate_target = sinkrate_target; +} + +void CombinedControllerConfigurationHandler::setLateralAccelMax(float lateral_accel_max) +{ + _lateral_configuration_current_cycle.lateral_accel_max = lateral_accel_max; +} + +void CombinedControllerConfigurationHandler::setEnforceLowHeightCondition(bool low_height_condition) +{ + _longitudinal_configuration_current_cycle.enforce_low_height_condition = low_height_condition; +} + +void CombinedControllerConfigurationHandler::resetLastPublishTime() +{ + _time_last_longitudinal_publish = _time_last_lateral_publish = 0; +} diff --git a/src/modules/fw_pos_control/ControllerConfigurationHandler.hpp b/src/modules/fw_pos_control/ControllerConfigurationHandler.hpp new file mode 100644 index 0000000000..73cfc78e4b --- /dev/null +++ b/src/modules/fw_pos_control/ControllerConfigurationHandler.hpp @@ -0,0 +1,113 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + +/** + * @file CombinedControllerConfigurationHandler.hpp + */ +#ifndef PX4_CONTROLLERCONFIGURATIONHANDLER_HPP +#define PX4_CONTROLLERCONFIGURATIONHANDLER_HPP + +#include +#include +#include +#include + +static constexpr longitudinal_control_configuration_s empty_longitudinal_control_configuration = {.timestamp = 0, .pitch_min = NAN, .pitch_max = NAN, .throttle_min = NAN, .throttle_max = NAN, .climb_rate_target = NAN, .sink_rate_target = NAN, .speed_weight = NAN, .enforce_low_height_condition = false, .disable_underspeed_protection = false }; +static constexpr lateral_control_configuration_s empty_lateral_control_configuration = {.timestamp = 0, .lateral_accel_max = NAN}; + + +class CombinedControllerConfigurationHandler +{ +public: + CombinedControllerConfigurationHandler() = default; + ~CombinedControllerConfigurationHandler() = default; + + void update(const hrt_abstime now); + + void setEnforceLowHeightCondition(bool low_height_condition); + + void setThrottleMax(float throttle_max); + + void setThrottleMin(float throttle_min); + + void setSpeedWeight(float speed_weight); + + void setPitchMin(const float pitch_min); + + void setPitchMax(const float pitch_max); + + void setClimbRateTarget(float climbrate_target); + + void setDisableUnderspeedProtection(bool disable); + + void setSinkRateTarget(const float sinkrate_target); + + void setLateralAccelMax(float lateral_accel_max); + + void resetLastPublishTime(); + +private: + bool booleanValueChanged(bool new_value, bool current_value) + { + return current_value != new_value; + } + + bool floatValueChanged(float new_value, float current_value) + { + bool diff; + + if (PX4_ISFINITE(new_value)) { + diff = PX4_ISFINITE(current_value) ? (fabsf(new_value - current_value) > FLT_EPSILON) : true; + + } else { + diff = PX4_ISFINITE(current_value); + } + + return diff; + } + + bool _lateral_updated{false}; + bool _longitudinal_updated{false}; + + hrt_abstime _time_last_longitudinal_publish{0}; + hrt_abstime _time_last_lateral_publish{0}; + + uORB::PublicationData _lateral_publisher{ORB_ID(lateral_control_configuration)}; + uORB::PublicationData _longitudinal_publisher{ORB_ID(longitudinal_control_configuration)}; + + lateral_control_configuration_s _lateral_configuration_current_cycle{empty_lateral_control_configuration}; + longitudinal_control_configuration_s _longitudinal_configuration_current_cycle {empty_longitudinal_control_configuration}; +}; + +#endif //PX4_CONTROLLERCONFIGURATIONHANDLER_HPP diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index de00c74b59..328a556be2 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2013-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -34,6 +34,7 @@ #include "FixedwingPositionControl.hpp" #include +#include using math::constrain; using math::max; @@ -48,41 +49,30 @@ using matrix::Vector2d; using matrix::Vector3f; using matrix::wrap_pi; -FixedwingPositionControl::FixedwingPositionControl(bool vtol) : +const fixed_wing_lateral_setpoint_s empty_lateral_control_setpoint = {.timestamp = 0, .course = NAN, .airspeed_direction = NAN, .lateral_acceleration = NAN}; +const fixed_wing_longitudinal_setpoint_s empty_longitudinal_control_setpoint = {.timestamp = 0, .altitude = NAN, .height_rate = NAN, .equivalent_airspeed = NAN, .pitch_direct = NAN, .throttle_direct = NAN}; + +FixedwingPositionControl::FixedwingPositionControl() : ModuleParams(nullptr), WorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers), - _attitude_sp_pub(vtol ? ORB_ID(fw_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)), _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")), _launchDetector(this), _runway_takeoff(this) #ifdef CONFIG_FIGURE_OF_EIGHT - , _figure_eight(_npfg, _wind_vel, _eas2tas) + , _figure_eight(_directional_guidance, _wind_vel) #endif // CONFIG_FIGURE_OF_EIGHT { - // limit to 50 Hz _local_pos_sub.set_interval_ms(20); - _pos_ctrl_status_pub.advertise(); _pos_ctrl_landing_status_pub.advertise(); - _tecs_status_pub.advertise(); _launch_detection_status_pub.advertise(); _landing_gear_pub.advertise(); - _flaps_setpoint_pub.advertise(); _spoilers_setpoint_pub.advertise(); + _fixed_wing_lateral_guidance_status_pub.advertise(); - _airspeed_slew_rate_controller.setSlewRate(ASPD_SP_SLEW_RATE); - - /* fetch initial parameter values */ parameters_update(); - - _roll_slew_rate.setSlewRate(radians(_param_fw_pn_r_slew_max.get())); - _roll_slew_rate.setForcedValue(0.f); - - _tecs_alt_time_const_slew_rate.setSlewRate(TECS_ALT_TIME_CONST_SLEW_RATE); - _tecs_alt_time_const_slew_rate.setForcedValue(_param_fw_t_h_error_tc.get() * _param_fw_thrtc_sc.get()); - } FixedwingPositionControl::~FixedwingPositionControl() @@ -106,51 +96,13 @@ FixedwingPositionControl::parameters_update() { updateParams(); - _performance_model.updateParameters(); - - _roll_slew_rate.setSlewRate(radians(_param_fw_pn_r_slew_max.get())); - - // NPFG parameters - _npfg.setPeriod(_param_npfg_period.get()); - _npfg.setDamping(_param_npfg_damping.get()); - _npfg.enablePeriodLB(_param_npfg_en_period_lb.get()); - _npfg.enablePeriodUB(_param_npfg_en_period_ub.get()); - _npfg.enableMinGroundSpeed(_param_npfg_en_min_gsp.get()); - _npfg.enableTrackKeeping(_param_npfg_en_track_keeping.get()); - _npfg.enableWindExcessRegulation(_param_npfg_en_wind_reg.get()); - _npfg.setMinGroundSpeed(_param_fw_gnd_spd_min.get()); - _npfg.setMaxTrackKeepingMinGroundSpeed(_param_npfg_track_keeping_gsp_max.get()); - _npfg.setRollTimeConst(_param_npfg_roll_time_const.get()); - _npfg.setSwitchDistanceMultiplier(_param_npfg_switch_distance_multiplier.get()); - _npfg.setRollLimit(radians(_param_fw_r_lim.get())); - _npfg.setPeriodSafetyFactor(_param_npfg_period_safety_factor.get()); - - // TECS parameters - _tecs.set_max_climb_rate(_performance_model.getMaximumClimbRate(_air_density)); - _tecs.set_max_sink_rate(_param_fw_t_sink_max.get()); - _tecs.set_min_sink_rate(_performance_model.getMinimumSinkRate(_air_density)); - _tecs.set_speed_weight(_param_fw_t_spdweight.get()); - _tecs.set_equivalent_airspeed_trim(_performance_model.getCalibratedTrimAirspeed()); - _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); - _tecs.set_equivalent_airspeed_max(_performance_model.getMaximumCalibratedAirspeed()); - _tecs.set_throttle_damp(_param_fw_t_thr_damping.get()); - _tecs.set_integrator_gain_throttle(_param_fw_t_thr_integ.get()); - _tecs.set_integrator_gain_pitch(_param_fw_t_I_gain_pit.get()); - _tecs.set_throttle_slewrate(_param_fw_thr_slew_max.get()); - _tecs.set_vertical_accel_limit(_param_fw_t_vert_acc.get()); - _tecs.set_roll_throttle_compensation(_param_fw_t_rll2thr.get()); - _tecs.set_pitch_damping(_param_fw_t_ptch_damp.get()); - _tecs.set_altitude_error_time_constant(_param_fw_t_h_error_tc.get()); - _tecs.set_fast_descend_altitude_error(_param_fw_t_fast_alt_err.get()); - _tecs.set_altitude_rate_ff(_param_fw_t_hrate_ff.get()); - _tecs.set_airspeed_error_time_constant(_param_fw_t_tas_error_tc.get()); - _tecs.set_ste_rate_time_const(_param_ste_rate_time_const.get()); - _tecs.set_seb_rate_ff_gain(_param_seb_rate_ff.get()); - _tecs.set_airspeed_measurement_std_dev(_param_speed_standard_dev.get()); - _tecs.set_airspeed_rate_measurement_std_dev(_param_speed_rate_standard_dev.get()); - _tecs.set_airspeed_filter_process_std_dev(_param_process_noise_standard_dev.get()); - - _performance_model.runSanityChecks(); + _directional_guidance.setPeriod(_param_npfg_period.get()); + _directional_guidance.setDamping(_param_npfg_damping.get()); + _directional_guidance.enablePeriodLB(_param_npfg_en_period_lb.get()); + _directional_guidance.enablePeriodUB(_param_npfg_en_period_ub.get()); + _directional_guidance.setRollTimeConst(_param_npfg_roll_time_const.get()); + _directional_guidance.setSwitchDistanceMultiplier(_param_npfg_switch_distance_multiplier.get()); + _directional_guidance.setPeriodSafetyFactor(_param_npfg_period_safety_factor.get()); } void @@ -207,45 +159,25 @@ FixedwingPositionControl::vehicle_command_poll() void FixedwingPositionControl::airspeed_poll() { - bool airspeed_valid = _airspeed_valid; airspeed_validated_s airspeed_validated; if (_param_fw_use_airspd.get() && _airspeed_validated_sub.update(&airspeed_validated)) { - _eas2tas = 1.0f; //this is the default value, taken in case of invalid airspeed - - // do not use synthetic airspeed as this would create a thrust loop + // do not use synthetic airspeed as it's for the use here not reliable enough if (PX4_ISFINITE(airspeed_validated.calibrated_airspeed_m_s) - && PX4_ISFINITE(airspeed_validated.true_airspeed_m_s) && airspeed_validated.airspeed_source != airspeed_validated_s::SYNTHETIC) { - airspeed_valid = true; - - _time_airspeed_last_valid = airspeed_validated.timestamp; _airspeed_eas = airspeed_validated.calibrated_airspeed_m_s; - - _eas2tas = constrain(airspeed_validated.true_airspeed_m_s / airspeed_validated.calibrated_airspeed_m_s, 0.9f, 2.0f); - - } else { - airspeed_valid = false; - } - - } else { - // no airspeed updates for one second - if (airspeed_valid && (hrt_elapsed_time(&_time_airspeed_last_valid) > 1_s)) { - airspeed_valid = false; } } - // update TECS if validity changed - if (airspeed_valid != _airspeed_valid) { - _tecs.enable_airspeed(airspeed_valid); - _airspeed_valid = airspeed_valid; - } + // no airspeed updates for one second --> declare invalid + // this flag is used for some logic like: exiting takeoff, flaps retraction + _airspeed_valid = hrt_elapsed_time(&_time_airspeed_last_valid) < 1_s; } void -FixedwingPositionControl::wind_poll() +FixedwingPositionControl::wind_poll(const hrt_abstime now) { if (_wind_sub.updated()) { wind_s wind; @@ -255,14 +187,14 @@ FixedwingPositionControl::wind_poll() _wind_valid = PX4_ISFINITE(wind.windspeed_north) && PX4_ISFINITE(wind.windspeed_east); - _time_wind_last_received = hrt_absolute_time(); + _time_wind_last_received = now; _wind_vel(0) = wind.windspeed_north; _wind_vel(1) = wind.windspeed_east; } else { // invalidate wind estimate usage (and correspondingly NPFG, if enabled) after subscription timeout - _wind_valid = _wind_valid && (hrt_absolute_time() - _time_wind_last_received) < WIND_EST_TIMEOUT; + _wind_valid = _wind_valid && (now - _time_wind_last_received) < WIND_EST_TIMEOUT; } if (!_wind_valid) { @@ -294,18 +226,17 @@ FixedwingPositionControl::manual_control_setpoint_poll() } } - void FixedwingPositionControl::vehicle_attitude_poll() { - vehicle_attitude_s att; + vehicle_attitude_s vehicle_attitude; - if (_vehicle_attitude_sub.update(&att)) { + if (_vehicle_attitude_sub.update(&vehicle_attitude)) { vehicle_angular_velocity_s angular_velocity{}; _vehicle_angular_velocity_sub.copy(&angular_velocity); const Vector3f rates{angular_velocity.xyz}; - Dcmf R{Quatf(att.q)}; + Dcmf R{Quatf(vehicle_attitude.q)}; // if the vehicle is a tailsitter we have to rotate the attitude by the pitch offset // between multirotor and fixed wing flight @@ -320,180 +251,33 @@ FixedwingPositionControl::vehicle_attitude_poll() } const Eulerf euler_angles(R); - _pitch = euler_angles(1); _yaw = euler_angles(2); - Vector3f body_acceleration = R.transpose() * Vector3f{_local_pos.ax, _local_pos.ay, _local_pos.az}; + const Vector3f body_acceleration = R.transpose() * Vector3f{_local_pos.ax, _local_pos.ay, _local_pos.az}; _body_acceleration_x = body_acceleration(0); - Vector3f body_velocity = R.transpose() * Vector3f{_local_pos.vx, _local_pos.vy, _local_pos.vz}; + const Vector3f body_velocity = R.transpose() * Vector3f{_local_pos.vx, _local_pos.vy, _local_pos.vz}; _body_velocity_x = body_velocity(0); - - // load factor due to banking - _tecs.set_load_factor(getLoadFactor()); } } float FixedwingPositionControl::get_manual_airspeed_setpoint() { - - float altctrl_airspeed = _performance_model.getCalibratedTrimAirspeed(); + float manual_airspeed_setpoint = NAN; if (_param_fw_pos_stk_conf.get() & STICK_CONFIG_ENABLE_AIRSPEED_SP_MANUAL_BIT) { // neutral throttle corresponds to trim airspeed - return math::interpolateNXY(_manual_control_setpoint_for_airspeed, + manual_airspeed_setpoint = math::interpolateNXY(_manual_control_setpoint_for_airspeed, {-1.f, 0.f, 1.f}, - {_performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), altctrl_airspeed, _performance_model.getMaximumCalibratedAirspeed()}); + {_param_fw_airspd_min.get(), _param_fw_airspd_trim.get(), _param_fw_airspd_max.get()}); } else if (PX4_ISFINITE(_commanded_manual_airspeed_setpoint)) { - altctrl_airspeed = constrain(_commanded_manual_airspeed_setpoint, - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), - _performance_model.getMaximumCalibratedAirspeed()); + // override stick by commanded airspeed + manual_airspeed_setpoint = _commanded_manual_airspeed_setpoint; } - return altctrl_airspeed; -} - -float -FixedwingPositionControl::adapt_airspeed_setpoint(const float control_interval, float calibrated_airspeed_setpoint, - float calibrated_min_airspeed, const Vector2f &ground_speed, bool in_takeoff_situation) -{ - // --- airspeed *constraint adjustments --- - - // Aditional option to increase the min airspeed setpoint based on wind estimate for more stability in higher winds. - if (!in_takeoff_situation && _airspeed_valid && _wind_valid && _param_fw_wind_arsp_sc.get() > FLT_EPSILON) { - calibrated_min_airspeed = math::min(calibrated_min_airspeed + _param_fw_wind_arsp_sc.get() * - _wind_vel.length(), _performance_model.getMaximumCalibratedAirspeed()); - } - - // --- airspeed *setpoint adjustments --- - - if (!PX4_ISFINITE(calibrated_airspeed_setpoint) || calibrated_airspeed_setpoint <= FLT_EPSILON) { - calibrated_airspeed_setpoint = _performance_model.getCalibratedTrimAirspeed(); - } - - // Adapt cruise airspeed when otherwise the min groundspeed couldn't be maintained - if (!_wind_valid && !in_takeoff_situation) { - /* - * This error value ensures that a plane (as long as its throttle capability is - * not exceeded) travels towards a waypoint (and is not pushed more and more away - * by wind). Not countering this would lead to a fly-away. Only non-zero in presence - * of sufficient wind. "minimum ground speed undershoot". - */ - const float ground_speed_body = _body_velocity_x; - - if (ground_speed_body < _param_fw_gnd_spd_min.get()) { - calibrated_airspeed_setpoint += _param_fw_gnd_spd_min.get() - ground_speed_body; - } - } - - calibrated_airspeed_setpoint = constrain(calibrated_airspeed_setpoint, calibrated_min_airspeed, - _performance_model.getMaximumCalibratedAirspeed()); - - // initialize the airspeed setpoint to the max(current airsped, min airspeed) - if (!PX4_ISFINITE(_airspeed_slew_rate_controller.getState()) - || !_tecs_is_running) { - _airspeed_slew_rate_controller.setForcedValue(math::max(calibrated_min_airspeed, _airspeed_eas)); - } - - // reset the airspeed setpoint to the min airspeed if the min airspeed changes while in operation - if (_airspeed_slew_rate_controller.getState() < calibrated_min_airspeed) { - _airspeed_slew_rate_controller.setForcedValue(calibrated_min_airspeed); - } - - if (control_interval > FLT_EPSILON) { - // constrain airspeed setpoint changes with slew rate of ASPD_SP_SLEW_RATE m/s/s - _airspeed_slew_rate_controller.update(calibrated_airspeed_setpoint, control_interval); - } - - if (_airspeed_slew_rate_controller.getState() > _performance_model.getMaximumCalibratedAirspeed()) { - _airspeed_slew_rate_controller.setForcedValue(_performance_model.getMaximumCalibratedAirspeed()); - } - - return _airspeed_slew_rate_controller.getState(); -} - -void -FixedwingPositionControl::tecs_status_publish(float alt_sp, float equivalent_airspeed_sp, - float true_airspeed_derivative_raw, float throttle_trim) -{ - tecs_status_s tecs_status{}; - - const TECS::DebugOutput &debug_output{_tecs.getStatus()}; - - tecs_status.altitude_sp = alt_sp; - tecs_status.altitude_reference = debug_output.altitude_reference; - tecs_status.altitude_time_constant = _tecs.get_altitude_error_time_constant(); - tecs_status.height_rate_reference = debug_output.height_rate_reference; - tecs_status.height_rate_direct = debug_output.height_rate_direct; - tecs_status.height_rate_setpoint = debug_output.control.altitude_rate_control; - tecs_status.height_rate = -_local_pos.vz; - tecs_status.equivalent_airspeed_sp = equivalent_airspeed_sp; - tecs_status.true_airspeed_sp = debug_output.true_airspeed_sp; - tecs_status.true_airspeed_filtered = debug_output.true_airspeed_filtered; - tecs_status.true_airspeed_derivative_sp = debug_output.control.true_airspeed_derivative_control; - tecs_status.true_airspeed_derivative = debug_output.true_airspeed_derivative; - tecs_status.true_airspeed_derivative_raw = true_airspeed_derivative_raw; - tecs_status.total_energy_rate = debug_output.control.total_energy_rate_estimate; - tecs_status.total_energy_balance_rate = debug_output.control.energy_balance_rate_estimate; - tecs_status.total_energy_rate_sp = debug_output.control.total_energy_rate_sp; - tecs_status.total_energy_balance_rate_sp = debug_output.control.energy_balance_rate_sp; - tecs_status.throttle_integ = debug_output.control.throttle_integrator; - tecs_status.pitch_integ = debug_output.control.pitch_integrator; - tecs_status.throttle_sp = _tecs.get_throttle_setpoint(); - tecs_status.pitch_sp_rad = _tecs.get_pitch_setpoint(); - tecs_status.throttle_trim = throttle_trim; - tecs_status.underspeed_ratio = _tecs.get_underspeed_ratio(); - tecs_status.fast_descend_ratio = debug_output.fast_descend; - - tecs_status.timestamp = hrt_absolute_time(); - - _tecs_status_pub.publish(tecs_status); -} - -void -FixedwingPositionControl::status_publish() -{ - position_controller_status_s pos_ctrl_status = {}; - - npfg_status_s npfg_status = {}; - - npfg_status.wind_est_valid = _wind_valid; - - const float bearing = _npfg.getBearing(); // dont repeat atan2 calc - - pos_ctrl_status.nav_bearing = bearing; - pos_ctrl_status.target_bearing = _target_bearing; - pos_ctrl_status.xtrack_error = _npfg.getTrackError(); - pos_ctrl_status.acceptance_radius = _npfg.switchDistance(500.0f); - - npfg_status.lat_accel = _npfg.getLateralAccel(); - npfg_status.lat_accel_ff = _npfg.getLateralAccelFF(); - npfg_status.heading_ref = _npfg.getHeadingRef(); - npfg_status.bearing = bearing; - npfg_status.bearing_feas = _npfg.getBearingFeas(); - npfg_status.bearing_feas_on_track = _npfg.getOnTrackBearingFeas(); - npfg_status.signed_track_error = _npfg.getTrackError(); - npfg_status.track_error_bound = _npfg.getTrackErrorBound(); - npfg_status.airspeed_ref = _npfg.getAirspeedRef(); - npfg_status.min_ground_speed_ref = _npfg.getMinGroundSpeedRef(); - npfg_status.adapted_period = _npfg.getAdaptedPeriod(); - npfg_status.p_gain = _npfg.getPGain(); - npfg_status.time_const = _npfg.getTimeConst(); - npfg_status.can_run_factor = _npfg.canRun(_local_pos, _wind_valid); - npfg_status.timestamp = hrt_absolute_time(); - - _npfg_status_pub.publish(npfg_status); - - pos_ctrl_status.wp_dist = get_distance_to_next_waypoint(_current_latitude, _current_longitude, - _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon); - - pos_ctrl_status.timestamp = hrt_absolute_time(); - - pos_ctrl_status.type = _position_sp_type; - - _pos_ctrl_status_pub.publish(pos_ctrl_status); + return manual_airspeed_setpoint; } void @@ -509,47 +293,6 @@ FixedwingPositionControl::landing_status_publish() _pos_ctrl_landing_status_pub.publish(pos_ctrl_landing_status); } -float FixedwingPositionControl::getCorrectedNpfgRollSetpoint() -{ - // Scale the npfg output to zero if npfg is not certain for correct output - float new_roll_setpoint(_npfg.getRollSetpoint()); - const float can_run_factor(constrain(_npfg.canRun(_local_pos, _wind_valid), 0.f, 1.f)); - - hrt_abstime now{hrt_absolute_time()}; - - // Warn the user when the scale is less than 90% for at least 2 seconds (disable in transition) - - // If the npfg was not running before, reset the user warning variables. - if ((now - _time_since_last_npfg_call) > ROLL_WARNING_TIMEOUT) { - _need_report_npfg_uncertain_condition = true; - _time_since_first_reduced_roll = 0U; - } - - if (_vehicle_status.in_transition_mode || can_run_factor > ROLL_WARNING_CAN_RUN_THRESHOLD || _landed) { - // NPFG reports a good condition or we are in transition, reset the user warning variables. - _need_report_npfg_uncertain_condition = true; - _time_since_first_reduced_roll = 0U; - - } else if (_need_report_npfg_uncertain_condition) { - if (_time_since_first_reduced_roll == 0U) { - _time_since_first_reduced_roll = now; - } - - if ((now - _time_since_first_reduced_roll) > ROLL_WARNING_TIMEOUT) { - _need_report_npfg_uncertain_condition = false; - events::send(events::ID("npfg_roll_command_uncertain"), events::Log::Warning, - "Roll command reduced due to uncertain velocity/wind estimates!"); - } - - } else { - // Nothing to do, already reported. - } - - _time_since_last_npfg_call = now; - - return can_run_factor * (new_roll_setpoint); -} - void FixedwingPositionControl::updateLandingAbortStatus(const uint8_t new_abort_status) { @@ -591,76 +334,18 @@ FixedwingPositionControl::updateLandingAbortStatus(const uint8_t new_abort_statu } } -void -FixedwingPositionControl::get_waypoint_heading_distance(float heading, position_setpoint_s &waypoint_prev, - position_setpoint_s &waypoint_next, bool flag_init) -{ - position_setpoint_s temp_prev = waypoint_prev; - position_setpoint_s temp_next = waypoint_next; - - if (flag_init) { - // previous waypoint: HDG_HOLD_SET_BACK_DIST meters behind us - waypoint_from_heading_and_distance(_current_latitude, _current_longitude, heading + radians(180.0f), - HDG_HOLD_SET_BACK_DIST, &temp_prev.lat, &temp_prev.lon); - - // next waypoint: HDG_HOLD_DIST_NEXT meters in front of us - waypoint_from_heading_and_distance(_current_latitude, _current_longitude, heading, - HDG_HOLD_DIST_NEXT, &temp_next.lat, &temp_next.lon); - - } else { - // use the existing flight path from prev to next - - // previous waypoint: shifted HDG_HOLD_REACHED_DIST + HDG_HOLD_SET_BACK_DIST - create_waypoint_from_line_and_dist(waypoint_next.lat, waypoint_next.lon, waypoint_prev.lat, waypoint_prev.lon, - HDG_HOLD_REACHED_DIST + HDG_HOLD_SET_BACK_DIST, &temp_prev.lat, &temp_prev.lon); - - // next waypoint: shifted -(HDG_HOLD_DIST_NEXT + HDG_HOLD_REACHED_DIST) - create_waypoint_from_line_and_dist(waypoint_next.lat, waypoint_next.lon, waypoint_prev.lat, waypoint_prev.lon, - -(HDG_HOLD_REACHED_DIST + HDG_HOLD_DIST_NEXT), &temp_next.lat, &temp_next.lon); - } - - waypoint_prev = temp_prev; - waypoint_prev.alt = _current_altitude; - - waypoint_next = temp_next; - waypoint_next.alt = _current_altitude; -} - float FixedwingPositionControl::getManualHeightRateSetpoint() { - /* - * The complete range is -1..+1, so this is 6% - * of the up or down range or 3% of the total range. - */ - const float deadBand = 0.06f; + float height_rate_setpoint = 0.f; - /* - * The correct scaling of the complete range needs - * to account for the missing part of the slope - * due to the deadband - */ - const float factor = 1.0f - deadBand; - - float height_rate_setpoint = 0.0f; - - /* - * Manual control has as convention the rotation around - * an axis. Positive X means to rotate positively around - * the X axis in NED frame, which is pitching down - */ - if (_manual_control_setpoint_for_height_rate > deadBand) { - /* pitching down */ - float pitch = -(_manual_control_setpoint_for_height_rate - deadBand) / factor; - height_rate_setpoint = pitch * _param_sinkrate_target.get(); - - } else if (_manual_control_setpoint_for_height_rate < - deadBand) { - /* pitching up */ - float pitch = -(_manual_control_setpoint_for_height_rate + deadBand) / factor; - const float climb_rate_target = _param_climbrate_target.get(); - - height_rate_setpoint = pitch * climb_rate_target; + if (_manual_control_setpoint_for_height_rate >= FLT_EPSILON) { + height_rate_setpoint = math::interpolate(math::deadzone(_manual_control_setpoint_for_height_rate, + kStickDeadBand), 0, 1.f, 0.f, -_param_sinkrate_target.get()); + } else { + height_rate_setpoint = math::interpolate(math::deadzone(_manual_control_setpoint_for_height_rate, + kStickDeadBand), -1., 0.f, _param_climbrate_target.get(), 0.f); } return height_rate_setpoint; @@ -670,7 +355,7 @@ void FixedwingPositionControl::updateManualTakeoffStatus() { if (!_completed_manual_takeoff) { - const bool at_controllable_airspeed = _airspeed_eas > _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()) + const bool at_controllable_airspeed = _airspeed_eas > _param_fw_airspd_min.get() || !_airspeed_valid; const bool is_hovering = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && _control_mode.flag_armed; @@ -687,7 +372,7 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) return; // do not publish the setpoint } - FW_POSCTRL_MODE commanded_position_control_mode = _control_mode_current; + const FW_POSCTRL_MODE previous_position_control_mode = _control_mode_current; _skipping_takeoff_detection = false; const bool doing_backtransition = _vehicle_status.in_transition_mode && !_vehicle_status.in_transition_to_fw; @@ -727,7 +412,7 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) } else { _control_mode_current = FW_POSCTRL_MODE_AUTO_TAKEOFF; - if (commanded_position_control_mode != FW_POSCTRL_MODE_AUTO_TAKEOFF && !_landed) { + if (previous_position_control_mode != FW_POSCTRL_MODE_AUTO_TAKEOFF && !_landed) { // skip takeoff detection when switching from any other mode, auto or manual, // while already in air. // TODO: find a better place for / way of doing this @@ -758,8 +443,8 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) // failsafe modes engaged if position estimate is invalidated - if (commanded_position_control_mode != FW_POSCTRL_MODE_AUTO_ALTITUDE - && commanded_position_control_mode != FW_POSCTRL_MODE_AUTO_CLIMBRATE) { + if (previous_position_control_mode != FW_POSCTRL_MODE_AUTO_ALTITUDE + && previous_position_control_mode != FW_POSCTRL_MODE_AUTO_CLIMBRATE) { // reset timer the first time we switch into this mode _time_in_fixed_bank_loiter = now; } @@ -770,7 +455,7 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) } else if (hrt_elapsed_time(&_time_in_fixed_bank_loiter) < (_param_nav_gpsf_lt.get() * 1_s) && !_vehicle_status.in_transition_mode) { - if (commanded_position_control_mode != FW_POSCTRL_MODE_AUTO_ALTITUDE) { + if (previous_position_control_mode != FW_POSCTRL_MODE_AUTO_ALTITUDE) { // Need to init because last loop iteration was in a different mode events::send(events::ID("fixedwing_position_control_fb_loiter"), events::Log::Critical, "Start loiter with fixed bank angle"); @@ -779,7 +464,7 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) _control_mode_current = FW_POSCTRL_MODE_AUTO_ALTITUDE; } else { - if (commanded_position_control_mode != FW_POSCTRL_MODE_AUTO_CLIMBRATE && !_vehicle_status.in_transition_mode) { + if (previous_position_control_mode != FW_POSCTRL_MODE_AUTO_CLIMBRATE && !_vehicle_status.in_transition_mode) { events::send(events::ID("fixedwing_position_control_descend"), events::Log::Critical, "Start descending"); } @@ -788,19 +473,11 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) } else if (_control_mode.flag_control_manual_enabled && _control_mode.flag_control_position_enabled) { - if (commanded_position_control_mode != FW_POSCTRL_MODE_MANUAL_POSITION) { + if (previous_position_control_mode != FW_POSCTRL_MODE_MANUAL_POSITION) { /* Need to init because last loop iteration was in a different mode */ _hdg_hold_yaw = _yaw; // yaw is not controlled, so set setpoint to current yaw _hdg_hold_enabled = false; // this makes sure the waypoints are reset below _yaw_lock_engaged = false; - - /* reset setpoints from other modes (auto) otherwise we won't - * level out without new manual input */ - float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); - float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - const Eulerf current_setpoint(Quatf(_att_sp.q_d)); - const Quatf setpoint(Eulerf(roll_body, current_setpoint.theta(), yaw_body)); - setpoint.copyTo(_att_sp.q_d); } _control_mode_current = FW_POSCTRL_MODE_MANUAL_POSITION; @@ -821,7 +498,6 @@ FixedwingPositionControl::update_in_air_states(const hrt_abstime now) if (_landed) { _completed_manual_takeoff = false; } - } void @@ -847,7 +523,6 @@ FixedwingPositionControl::move_position_setpoint_for_vtol_transition(position_se _transition_waypoint(1) = lon_transition; } - current_sp.lat = _transition_waypoint(0); current_sp.lon = _transition_waypoint(1); @@ -886,13 +561,7 @@ FixedwingPositionControl::control_auto(const float control_interval, const Vecto switch (position_sp_type) { case position_setpoint_s::SETPOINT_TYPE_IDLE: { - _att_sp.thrust_body[0] = 0.0f; - const float roll_body = 0.0f; - const float pitch_body = radians(_param_fw_psp_off.get()); - const float yaw_body = 0.0f; - - const Quatf setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - setpoint.copyTo(_att_sp.q_d); + control_idle(); break; } @@ -907,12 +576,12 @@ FixedwingPositionControl::control_auto(const float control_interval, const Vecto case position_setpoint_s::SETPOINT_TYPE_LOITER: #ifdef CONFIG_FIGURE_OF_EIGHT if (current_sp.loiter_pattern == position_setpoint_s::LOITER_TYPE_FIGUREEIGHT) { - controlAutoFigureEight(control_interval, curr_pos, ground_speed, pos_sp_prev, current_sp); + controlAutoFigureEight(control_interval, curr_pos, ground_speed, current_sp); } else #endif // CONFIG_FIGURE_OF_EIGHT { - control_auto_loiter(control_interval, curr_pos, ground_speed, pos_sp_prev, current_sp, pos_sp_next); + control_auto_loiter(control_interval, curr_pos, ground_speed, current_sp, pos_sp_next); } @@ -930,90 +599,89 @@ FixedwingPositionControl::control_auto(const float control_interval, const Vecto #endif // CONFIG_FIGURE_OF_EIGHT - /* Copy thrust output for publication, handle special cases */ - if (position_sp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { - - _att_sp.thrust_body[0] = 0.0f; - - } else { - // when we are landed state we want the motor to spin at idle speed - _att_sp.thrust_body[0] = (_landed) ? min(_param_fw_thr_idle.get(), 1.f) : get_tecs_thrust(); - } - if (!_vehicle_status.in_transition_to_fw) { publishLocalPositionSetpoint(current_sp); } } -void -FixedwingPositionControl::control_auto_fixed_bank_alt_hold(const float control_interval) +void FixedwingPositionControl::control_idle() { - const bool is_low_height = checkLowHeightConditions(); + const hrt_abstime now = hrt_absolute_time(); + fixed_wing_lateral_setpoint_s lateral_ctrl_sp {empty_lateral_control_setpoint}; + lateral_ctrl_sp.timestamp = now; + lateral_ctrl_sp.lateral_acceleration = 0.0f; + _lateral_ctrl_sp_pub.publish(lateral_ctrl_sp); - // only control altitude and airspeed ("fixed-bank loiter") - tecs_update_pitch_throttle(control_interval, - _current_altitude, - _performance_model.getCalibratedTrimAirspeed(), - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - _param_fw_thr_min.get(), - _param_fw_thr_max.get(), - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height); + fixed_wing_longitudinal_setpoint_s long_contrl_sp {empty_longitudinal_control_setpoint}; + long_contrl_sp.timestamp = now; + long_contrl_sp.pitch_direct = 0.f; + long_contrl_sp.throttle_direct = 0.0f; + _longitudinal_ctrl_sp_pub.publish(long_contrl_sp); - const float roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle - const float yaw_body = 0.f; + _ctrl_configuration_handler.setThrottleMax(0.0f); + _ctrl_configuration_handler.setThrottleMin(0.0f); +} + +void +FixedwingPositionControl::control_auto_fixed_bank_alt_hold() +{ + const hrt_abstime now = hrt_absolute_time(); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = now, + .altitude = _current_altitude, + .height_rate = NAN, + .equivalent_airspeed = NAN, + .pitch_direct = NAN, + .throttle_direct = NAN + }; + + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); + + float throttle_max = _param_fw_thr_max.get(); // Special case: if z or vz estimate is invalid we cannot control height anymore. To prevent a // "climb-away" we set the thrust to MIN in that case. if (_landed || !_local_pos.z_valid || !_local_pos.v_z_valid) { - _att_sp.thrust_body[0] = _param_fw_thr_min.get(); - - } else { - _att_sp.thrust_body[0] = min(get_tecs_thrust(), _param_fw_thr_max.get()); + throttle_max = _param_fw_thr_min.get(); } - const float pitch_body = get_tecs_pitch(); - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + _ctrl_configuration_handler.setThrottleMax(throttle_max); + fixed_wing_lateral_setpoint_s lateral_ctrl_sp = empty_lateral_control_setpoint; + lateral_ctrl_sp.timestamp = hrt_absolute_time(); + const float roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle + lateral_ctrl_sp.lateral_acceleration = rollAngleToLateralAccel(roll_body); + _lateral_ctrl_sp_pub.publish(lateral_ctrl_sp); } void -FixedwingPositionControl::control_auto_descend(const float control_interval) +FixedwingPositionControl::control_auto_descend() { // Hard-code descend rate to 0.5m/s. This is a compromise to give the system to recover, // but not letting it drift too far away. - const float descend_rate = -0.5f; - const bool disable_underspeed_handling = false; + const float descend_rate = 0.5f; - const bool is_low_height = checkLowHeightConditions(); + const hrt_abstime now = hrt_absolute_time(); - tecs_update_pitch_throttle(control_interval, - _current_altitude, - _performance_model.getCalibratedTrimAirspeed(), - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - _param_fw_thr_min.get(), - _param_fw_thr_max.get(), - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height, - disable_underspeed_handling, - descend_rate); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = now, + .altitude = NAN, + .height_rate = -descend_rate, + .equivalent_airspeed = NAN, + .pitch_direct = NAN, + .throttle_direct = NAN + }; + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); + + _ctrl_configuration_handler.setThrottleMax((_landed + || !_local_pos.v_z_valid) ? _param_fw_thr_min.get() : _param_fw_thr_max.get()); + + fixed_wing_lateral_setpoint_s lateral_ctrl_sp = empty_lateral_control_setpoint; + lateral_ctrl_sp.timestamp = now; const float roll_body = math::radians(_param_nav_gpsf_r.get()); // open loop loiter bank angle - const float yaw_body = 0.f; - - // Special case: if vz estimate is invalid we cannot control height rate anymore. To prevent a - // "climb-away" we set the thrust to MIN in that case. - _att_sp.thrust_body[0] = (_landed - || !_local_pos.v_z_valid) ? _param_fw_thr_min.get() : min(get_tecs_thrust(), _param_fw_thr_max.get()); - - const float pitch_body = get_tecs_pitch(); - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + lateral_ctrl_sp.lateral_acceleration = rollAngleToLateralAccel(roll_body); + _lateral_ctrl_sp_pub.publish(lateral_ctrl_sp); } uint8_t @@ -1031,13 +699,12 @@ FixedwingPositionControl::handle_setpoint_type(const position_setpoint_s &pos_sp /* current waypoint (the one currently heading for) */ curr_wp = Vector2d(pos_sp_curr.lat, pos_sp_curr.lon); - const float acc_rad = _npfg.switchDistance(500.0f); + const float acc_rad = _directional_guidance.switchDistance(500.0f); const bool approaching_vtol_backtransition = _vehicle_status.is_vtol && pos_sp_curr.type == position_setpoint_s::SETPOINT_TYPE_POSITION && _position_setpoint_current_valid && pos_sp_next.type == position_setpoint_s::SETPOINT_TYPE_LAND && _position_setpoint_next_valid; - // check if we should switch to loiter but only if we are not expecting a backtransition to happen if (pos_sp_curr.type == position_setpoint_s::SETPOINT_TYPE_POSITION && !approaching_vtol_backtransition) { @@ -1072,20 +739,8 @@ void FixedwingPositionControl::control_auto_position(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr) { - const float acc_rad = _npfg.switchDistance(500.0f); - float tecs_fw_thr_min; - float tecs_fw_thr_max; - - if (pos_sp_curr.gliding_enabled) { - /* enable gliding with this waypoint */ - _tecs.set_speed_weight(2.0f); - tecs_fw_thr_min = 0.0; - tecs_fw_thr_max = 0.0; - - } else { - tecs_fw_thr_min = _param_fw_thr_min.get(); - tecs_fw_thr_max = _param_fw_thr_max.get(); - } + const float acc_rad = _directional_guidance.switchDistance(500.0f); + const float target_airspeed = pos_sp_curr.cruising_speed > FLT_EPSILON ? pos_sp_curr.cruising_speed : NAN; // waypoint is a plain navigation waypoint float position_sp_alt = pos_sp_curr.alt; @@ -1122,149 +777,95 @@ FixedwingPositionControl::control_auto_position(const float control_interval, co } } - float target_airspeed = adapt_airspeed_setpoint(control_interval, pos_sp_curr.cruising_speed, - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), ground_speed); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = position_sp_alt, + .height_rate = NAN, + .equivalent_airspeed = target_airspeed, + .pitch_direct = NAN, + .throttle_direct = NAN + }; + + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); + + float throttle_min = NAN; + float throttle_max = NAN; + + if (pos_sp_curr.gliding_enabled) { + /* enable gliding with this waypoint */ + throttle_min = 0.0; + throttle_max = 0.0; + _ctrl_configuration_handler.setSpeedWeight(2.f); + } + + _ctrl_configuration_handler.setThrottleMax(throttle_max); + _ctrl_configuration_handler.setThrottleMin(throttle_min); Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; Vector2f curr_wp_local = _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon); - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); + DirectionalGuidanceOutput sp{}; if (_position_setpoint_previous_valid && pos_sp_prev.type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) { Vector2f prev_wp_local = _global_local_proj_ref.project(pos_sp_prev.lat, pos_sp_prev.lon); - navigateWaypoints(prev_wp_local, curr_wp_local, curr_pos_local, ground_speed, _wind_vel); + sp = navigateWaypoints(prev_wp_local, curr_wp_local, curr_pos_local, ground_speed, _wind_vel); } else { - navigateWaypoint(curr_wp_local, curr_pos_local, ground_speed, _wind_vel); + sp = navigateWaypoint(curr_wp_local, curr_pos_local, ground_speed, _wind_vel); } - float roll_body = getCorrectedNpfgRollSetpoint(); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - - float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - - const bool is_low_height = checkLowHeightConditions(); - - tecs_update_pitch_throttle(control_interval, - position_sp_alt, - target_airspeed, - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - tecs_fw_thr_min, - tecs_fw_thr_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height); - - const float pitch_body = get_tecs_pitch(); - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + fixed_wing_lateral_setpoint_s lateral_ctrl_sp{empty_lateral_control_setpoint}; + lateral_ctrl_sp.timestamp = hrt_absolute_time(); + lateral_ctrl_sp.course = sp.course_setpoint; + lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + _lateral_ctrl_sp_pub.publish(lateral_ctrl_sp); } void FixedwingPositionControl::control_auto_velocity(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { - float tecs_fw_thr_min; - float tecs_fw_thr_max; - - if (pos_sp_curr.gliding_enabled) { - /* enable gliding with this waypoint */ - _tecs.set_speed_weight(2.0f); - tecs_fw_thr_min = 0.0; - tecs_fw_thr_max = 0.0; - - } else { - tecs_fw_thr_min = _param_fw_thr_min.get(); - tecs_fw_thr_max = _param_fw_thr_max.get(); - } - - // waypoint is a plain navigation waypoint - float position_sp_alt = pos_sp_curr.alt; - - //Offboard velocity control Vector2f target_velocity{pos_sp_curr.vx, pos_sp_curr.vy}; - _target_bearing = wrap_pi(atan2f(target_velocity(1), target_velocity(0))); + const float target_bearing = wrap_pi(atan2f(target_velocity(1), target_velocity(0))); - float target_airspeed = adapt_airspeed_setpoint(control_interval, pos_sp_curr.cruising_speed, - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), ground_speed); + const Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; + const DirectionalGuidanceOutput sp = navigateBearing(curr_pos_local, target_bearing, ground_speed, _wind_vel); - Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateBearing(curr_pos_local, _target_bearing, ground_speed, _wind_vel); - float roll_body = getCorrectedNpfgRollSetpoint(); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); - float yaw_body = _yaw; - const bool disable_underspeed_handling = false; + const float target_airspeed = pos_sp_curr.cruising_speed > FLT_EPSILON ? pos_sp_curr.cruising_speed : NAN; - const bool is_low_height = checkLowHeightConditions(); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = pos_sp_curr.alt, + .height_rate = pos_sp_curr.vz, + .equivalent_airspeed = target_airspeed, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - tecs_update_pitch_throttle(control_interval, - position_sp_alt, - target_airspeed, - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - tecs_fw_thr_min, - tecs_fw_thr_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height, - disable_underspeed_handling, - pos_sp_curr.vz); - const float pitch_body = get_tecs_pitch(); + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + if (pos_sp_curr.gliding_enabled) { + _ctrl_configuration_handler.setThrottleMin(0.0f); + _ctrl_configuration_handler.setThrottleMax(0.0f); + _ctrl_configuration_handler.setSpeedWeight(2.0f); + } } void FixedwingPositionControl::control_auto_loiter(const float control_interval, const Vector2d &curr_pos, - const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr, + const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr, const position_setpoint_s &pos_sp_next) { + // current waypoint (the one currently heading for) + const Vector2d curr_wp = Vector2d(pos_sp_curr.lat, pos_sp_curr.lon); - Vector2d curr_wp{0, 0}; - Vector2d prev_wp{0, 0}; - - /* current waypoint (the one currently heading for) */ - curr_wp = Vector2d(pos_sp_curr.lat, pos_sp_curr.lon); - - if (_position_setpoint_previous_valid && pos_sp_prev.type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) { - prev_wp(0) = pos_sp_prev.lat; - prev_wp(1) = pos_sp_prev.lon; - - } else { - // No valid previous waypoint, go along the line between aircraft and current waypoint - prev_wp = curr_pos; - } - - float airspeed_sp = -1.f; - - if (PX4_ISFINITE(pos_sp_curr.cruising_speed) && - pos_sp_curr.cruising_speed > FLT_EPSILON) { - - airspeed_sp = pos_sp_curr.cruising_speed; - } - - float tecs_fw_thr_min; - float tecs_fw_thr_max; - - if (pos_sp_curr.gliding_enabled) { - /* enable gliding with this waypoint */ - _tecs.set_speed_weight(2.0f); - tecs_fw_thr_min = 0.0; - tecs_fw_thr_max = 0.0; - - } else { - tecs_fw_thr_min = _param_fw_thr_min.get(); - tecs_fw_thr_max = _param_fw_thr_max.get(); - } - - /* waypoint is a loiter waypoint */ float loiter_radius = pos_sp_curr.loiter_radius; if (fabsf(pos_sp_curr.loiter_radius) < FLT_EPSILON) { @@ -1275,41 +876,40 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons Vector2f curr_wp_local{_global_local_proj_ref.project(curr_wp(0), curr_wp(1))}; Vector2f vehicle_to_loiter_center{curr_wp_local - curr_pos_local}; - bool is_low_height = checkLowHeightConditions(); + const bool close_to_circle = vehicle_to_loiter_center.norm() < loiter_radius + _directional_guidance.switchDistance( + 500); - const bool close_to_circle = vehicle_to_loiter_center.norm() < loiter_radius + _npfg.switchDistance(500); + bool enforce_low_height{false}; + + float target_airspeed = pos_sp_curr.cruising_speed > FLT_EPSILON ? pos_sp_curr.cruising_speed : NAN; if (pos_sp_next.type == position_setpoint_s::SETPOINT_TYPE_LAND && _position_setpoint_next_valid && close_to_circle && _param_fw_lnd_earlycfg.get()) { // We're in a loiter directly before a landing WP. Enable our landing configuration (flaps, // landing airspeed and potentially tighter altitude control) already such that we don't // have to do this switch (which can cause significant altitude errors) close to the ground. + enforce_low_height = true; - // Just before landing, enforce low-height flight conditions for tighter altitude control - is_low_height = true; + if (_param_fw_lnd_airspd.get() > FLT_EPSILON) { + target_airspeed = _param_fw_lnd_airspd.get(); + } - airspeed_sp = (_param_fw_lnd_airspd.get() > FLT_EPSILON) ? _param_fw_lnd_airspd.get() : - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); _spoilers_setpoint = _param_fw_spoilers_lnd.get(); _new_landing_gear_position = landing_gear_s::GEAR_DOWN; } - float target_airspeed = adapt_airspeed_setpoint(control_interval, airspeed_sp, - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), - ground_speed); + const DirectionalGuidanceOutput sp = navigateLoiter(curr_wp_local, curr_pos_local, loiter_radius, + pos_sp_curr.loiter_direction_counter_clockwise, + ground_speed, + _wind_vel); - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateLoiter(curr_wp_local, curr_pos_local, loiter_radius, pos_sp_curr.loiter_direction_counter_clockwise, - ground_speed, - _wind_vel); - float roll_body = getCorrectedNpfgRollSetpoint(); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; - float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - - float alt_sp = pos_sp_curr.alt; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); if (_landing_abort_status) { if (pos_sp_curr.alt - _current_altitude < kClearanceAltitudeBuffer) { @@ -1318,47 +918,47 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons } else { // continue straight until vehicle has sufficient altitude - // keep flaps in landing configuration if the airspeed is below the min airspeed (keep deployed if airspeed not valid) - roll_body = 0.0f; + _ctrl_configuration_handler.setLateralAccelMax(0.0f); - if (!_airspeed_valid || _airspeed_eas < _performance_model.getMinimumCalibratedAirspeed()) { - _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); + // keep flaps in landing configuration if the airspeed is below the min airspeed (keep deployed if airspeed not valid) + if (!_airspeed_valid || _airspeed_eas < _param_fw_airspd_min.get()) { + _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); } else { _flaps_setpoint = 0.f; } } - is_low_height = true; // In low-height flight, TECS will control altitude tighter + enforce_low_height = true; } - tecs_update_pitch_throttle(control_interval, - alt_sp, - target_airspeed, - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - tecs_fw_thr_min, - tecs_fw_thr_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = pos_sp_curr.alt, + .height_rate = NAN, + .equivalent_airspeed = target_airspeed, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - const float pitch_body = get_tecs_pitch(); + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + if (pos_sp_curr.gliding_enabled) { + _ctrl_configuration_handler.setThrottleMin(0.0f); + _ctrl_configuration_handler.setThrottleMax(0.0f); + _ctrl_configuration_handler.setSpeedWeight(2.0f); + } + + _ctrl_configuration_handler.setEnforceLowHeightCondition(enforce_low_height); } #ifdef CONFIG_FIGURE_OF_EIGHT void FixedwingPositionControl::controlAutoFigureEight(const float control_interval, const Vector2d &curr_pos, - const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr) + const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { // airspeed settings - float target_airspeed = adapt_airspeed_setpoint(control_interval, pos_sp_curr.cruising_speed, - _performance_model.getMinimumCalibratedAirspeed(), ground_speed); - - // Lateral Control + const float target_airspeed = pos_sp_curr.cruising_speed > FLT_EPSILON ? pos_sp_curr.cruising_speed : NAN; Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; @@ -1369,47 +969,33 @@ FixedwingPositionControl::controlAutoFigureEight(const float control_interval, c params.loiter_orientation = pos_sp_curr.loiter_orientation; params.loiter_radius = pos_sp_curr.loiter_radius; - // Apply control - _figure_eight.updateSetpoint(curr_pos_local, ground_speed, params, target_airspeed); - float roll_body = _figure_eight.getRollSetpoint(); - target_airspeed = _figure_eight.getAirspeedSetpoint(); - _target_bearing = _figure_eight.getTargetBearing(); + const DirectionalGuidanceOutput sp = _figure_eight.updateSetpoint(curr_pos_local, ground_speed, params); + + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); + _closest_point_on_path = _figure_eight.getClosestPoint(); - // TECS - float tecs_fw_thr_min; - float tecs_fw_thr_max; + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = pos_sp_curr.alt, + .height_rate = NAN, + .equivalent_airspeed = target_airspeed, + .pitch_direct = NAN, + .throttle_direct = NAN + }; + + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); if (pos_sp_curr.gliding_enabled) { - /* enable gliding with this waypoint */ - _tecs.set_speed_weight(2.0f); - tecs_fw_thr_min = 0.0; - tecs_fw_thr_max = 0.0; - - } else { - tecs_fw_thr_min = _param_fw_thr_min.get(); - tecs_fw_thr_max = _param_fw_thr_max.get(); + _ctrl_configuration_handler.setThrottleMin(0.0f); + _ctrl_configuration_handler.setThrottleMax(0.0f); + _ctrl_configuration_handler.setSpeedWeight(2.0f); } - - const bool is_low_height = checkLowHeightConditions(); - - tecs_update_pitch_throttle(control_interval, - pos_sp_curr.alt, - target_airspeed, - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - tecs_fw_thr_min, - tecs_fw_thr_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height); - - // Yaw - float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - const float pitch_body = get_tecs_pitch(); - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); } void FixedwingPositionControl::publishFigureEightStatus(const position_setpoint_s pos_sp) @@ -1432,60 +1018,41 @@ void FixedwingPositionControl::control_auto_path(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { - float tecs_fw_thr_min; - float tecs_fw_thr_max; - - if (pos_sp_curr.gliding_enabled) { - /* enable gliding with this waypoint */ - _tecs.set_speed_weight(2.0f); - tecs_fw_thr_min = 0.0; - tecs_fw_thr_max = 0.0; - - } else { - tecs_fw_thr_min = _param_fw_thr_min.get(); - tecs_fw_thr_max = _param_fw_thr_max.get(); - } - - // waypoint is a plain navigation waypoint - float target_airspeed = adapt_airspeed_setpoint(control_interval, pos_sp_curr.cruising_speed, - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), ground_speed); + const float target_airspeed = pos_sp_curr.cruising_speed > FLT_EPSILON ? pos_sp_curr.cruising_speed : NAN; Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; Vector2f curr_wp_local = _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon); - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - // Navigate directly on position setpoint and path tangent - matrix::Vector2f velocity_2d(pos_sp_curr.vx, pos_sp_curr.vy); + const matrix::Vector2f velocity_2d(pos_sp_curr.vx, pos_sp_curr.vy); const float curvature = PX4_ISFINITE(_pos_sp_triplet.current.loiter_radius) ? 1 / _pos_sp_triplet.current.loiter_radius : 0.0f; - navigatePathTangent(curr_pos_local, curr_wp_local, velocity_2d.normalized(), ground_speed, _wind_vel, curvature); + const DirectionalGuidanceOutput sp = navigatePathTangent(curr_pos_local, curr_wp_local, velocity_2d.normalized(), + ground_speed, _wind_vel, curvature); - float roll_body = getCorrectedNpfgRollSetpoint(); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); - float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = pos_sp_curr.alt, + .height_rate = NAN, + .equivalent_airspeed = target_airspeed, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - const bool is_low_height = checkLowHeightConditions(); + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - tecs_update_pitch_throttle(control_interval, - pos_sp_curr.alt, - target_airspeed, - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - tecs_fw_thr_min, - tecs_fw_thr_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height); - - _att_sp.thrust_body[0] = min(get_tecs_thrust(), tecs_fw_thr_max); - const float pitch_body = get_tecs_pitch(); - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + if (pos_sp_curr.gliding_enabled) { + _ctrl_configuration_handler.setThrottleMin(0.0f); + _ctrl_configuration_handler.setThrottleMax(0.0f); + _ctrl_configuration_handler.setSpeedWeight(2.0f); + } } void @@ -1504,27 +1071,18 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo // (navigator will accept the takeoff as complete once crossing the clearance altitude) const float altitude_setpoint_amsl = clearance_altitude_amsl + kClearanceAltitudeBuffer; - Vector2f local_2D_position{_local_pos.x, _local_pos.y}; + const Vector2f local_2D_position{_local_pos.x, _local_pos.y}; const float takeoff_airspeed = (_param_fw_tko_airspd.get() > FLT_EPSILON) ? _param_fw_tko_airspd.get() : - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); - - float adjusted_min_airspeed = _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); - - if (takeoff_airspeed < adjusted_min_airspeed) { - // adjust underspeed detection bounds for takeoff airspeed - _tecs.set_equivalent_airspeed_min(takeoff_airspeed); - adjusted_min_airspeed = takeoff_airspeed; - } - - const bool is_low_height = checkLowHeightConditions(); + _param_fw_airspd_min.get(); if (_runway_takeoff.runwayTakeoffEnabled()) { if (!_runway_takeoff.isInitialized()) { - _runway_takeoff.init(now, _yaw, global_position); + _runway_takeoff.init(now); + _takeoff_init_position = global_position; _takeoff_ground_alt = _current_altitude; _launch_current_yaw = _yaw; - _airspeed_slew_rate_controller.setForcedValue(takeoff_airspeed); + // _airspeed_slew_rate_controller.setForcedValue(takeoff_airspeed); // TODO events::send(events::ID("fixedwing_position_control_takeoff"), events::Log::Info, "Takeoff on runway"); } @@ -1536,22 +1094,12 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _runway_takeoff.update(now, takeoff_airspeed, _airspeed_eas, _current_altitude - _takeoff_ground_alt, clearance_altitude_amsl - _takeoff_ground_alt); - // yaw control is disabled once in "taking off" state - _att_sp.fw_control_yaw_wheel = _runway_takeoff.controlYaw(); - // XXX: hacky way to pass through manual nose-wheel incrementing. need to clean this interface. if (_param_rwto_nudge.get()) { _att_sp.yaw_sp_move_rate = _manual_control_setpoint.yaw; } - // tune up the lateral position control guidance when on the ground - if (_runway_takeoff.controlYaw()) { - _npfg.setPeriod(_param_rwto_npfg_period.get()); - - } - - const Vector2f start_pos_local = _global_local_proj_ref.project(_runway_takeoff.getStartPosition()(0), - _runway_takeoff.getStartPosition()(1)); + const Vector2f start_pos_local = _global_local_proj_ref.project(_takeoff_init_position(0), _takeoff_init_position(1)); const Vector2f takeoff_waypoint_local = _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon); // by default set the takeoff bearing to the takeoff yaw, but override in a mission takeoff with bearing to takeoff WP @@ -1566,59 +1114,38 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo } } - float target_airspeed = adapt_airspeed_setpoint(control_interval, takeoff_airspeed, adjusted_min_airspeed, ground_speed, - true); + const DirectionalGuidanceOutput sp = navigateLine(start_pos_local, takeoff_bearing, local_2D_position, ground_speed, + _wind_vel); - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateLine(start_pos_local, takeoff_bearing, local_2D_position, ground_speed, _wind_vel); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = now; + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; - float roll_body = _runway_takeoff.getRoll(getCorrectedNpfgRollSetpoint()); + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; + const float roll_wingtip_strike = getMaxRollAngleNearGround(_current_altitude, _takeoff_ground_alt); + _ctrl_configuration_handler.setLateralAccelMax(rollAngleToLateralAccel(roll_wingtip_strike)); - // use npfg's bearing to commanded course, controlled via yaw angle while on runway - const float bearing = _npfg.getBearing(); - - // heading hold mode will override this bearing setpoint - float yaw_body = _runway_takeoff.getYaw(bearing); - - // update tecs const float pitch_max = _runway_takeoff.getMaxPitch(math::radians(_param_fw_p_lim_max.get())); const float pitch_min = _runway_takeoff.getMinPitch(math::radians(_takeoff_pitch_min.get()), math::radians(_param_fw_p_lim_min.get())); - if (_runway_takeoff.resetIntegrators()) { - // reset integrals except yaw (which also counts for the wheel controller) - _att_sp.reset_integral = true; + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = now, + .altitude = altitude_setpoint_amsl, + .height_rate = NAN, + .equivalent_airspeed = takeoff_airspeed, + .pitch_direct = _runway_takeoff.getPitch(), + .throttle_direct = _runway_takeoff.getThrottle(_param_fw_thr_idle.get()) + }; - // throttle is open loop anyway during ground roll, no need to wind up the integrator - _tecs.resetIntegrals(); - } + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - const bool disable_underspeed_handling = true; - - tecs_update_pitch_throttle(control_interval, - altitude_setpoint_amsl, - target_airspeed, - pitch_min, - pitch_max, - _param_fw_thr_min.get(), - _param_fw_thr_max.get(), - _param_sinkrate_target.get(), - _performance_model.getMaximumClimbRate(_air_density), - is_low_height, - disable_underspeed_handling); - - _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation - - const float pitch_body = _runway_takeoff.getPitch(get_tecs_pitch()); - _att_sp.thrust_body[0] = _runway_takeoff.getThrottle(_param_fw_thr_idle.get(), get_tecs_thrust()); - - roll_body = constrainRollNearGround(roll_body, _current_altitude, _takeoff_ground_alt); - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + _ctrl_configuration_handler.setPitchMin(pitch_min); + _ctrl_configuration_handler.setPitchMax(pitch_max); + _ctrl_configuration_handler.setClimbRateTarget(_param_fw_t_clmb_max.get()); + _ctrl_configuration_handler.setDisableUnderspeedProtection(true); _flaps_setpoint = _param_fw_flaps_to_scl.get(); @@ -1646,14 +1173,14 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo if (!_launch_detected && _launchDetector.getLaunchDetected() > launch_detection_status_s::STATE_WAITING_FOR_LAUNCH) { _launch_detected = true; - _launch_global_position = global_position; + _takeoff_init_position = global_position; _takeoff_ground_alt = _current_altitude; _launch_current_yaw = _yaw; - _airspeed_slew_rate_controller.setForcedValue(takeoff_airspeed); + // _airspeed_slew_rate_controller.setForcedValue(takeoff_airspeed); // TODO } - const Vector2f launch_local_position = _global_local_proj_ref.project(_launch_global_position(0), - _launch_global_position(1)); + const Vector2f launch_local_position = _global_local_proj_ref.project(_takeoff_init_position(0), + _takeoff_init_position(1)); const Vector2f takeoff_waypoint_local = _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon); // by default set the takeoff bearing to the takeoff yaw, but override in a mission takeoff with bearing to takeoff WP @@ -1672,61 +1199,52 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo if (_launchDetector.getLaunchDetected() > launch_detection_status_s::STATE_WAITING_FOR_LAUNCH) { /* Launch has been detected, hence we have to control the plane. */ - float target_airspeed = adapt_airspeed_setpoint(control_interval, takeoff_airspeed, adjusted_min_airspeed, ground_speed, - true); + const DirectionalGuidanceOutput sp = navigateLine(launch_local_position, takeoff_bearing, local_2D_position, + ground_speed, + _wind_vel); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = now; + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateLine(launch_local_position, takeoff_bearing, local_2D_position, ground_speed, _wind_vel); - float roll_body = getCorrectedNpfgRollSetpoint(); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); + const float roll_wingtip_strike = getMaxRollAngleNearGround(_current_altitude, _takeoff_ground_alt); + _ctrl_configuration_handler.setLateralAccelMax(rollAngleToLateralAccel(roll_wingtip_strike)); const float max_takeoff_throttle = (_launchDetector.getLaunchDetected() < launch_detection_status_s::STATE_FLYING) ? - _param_fw_thr_idle.get() : _param_fw_thr_max.get(); - const bool disable_underspeed_handling = true; + _param_fw_thr_idle.get() : NAN; + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = now, + .altitude = altitude_setpoint_amsl, + .height_rate = NAN, + .equivalent_airspeed = takeoff_airspeed, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - tecs_update_pitch_throttle(control_interval, - altitude_setpoint_amsl, - target_airspeed, - radians(_takeoff_pitch_min.get()), - radians(_param_fw_p_lim_max.get()), - _param_fw_thr_min.get(), - max_takeoff_throttle, - _param_sinkrate_target.get(), - _performance_model.getMaximumClimbRate(_air_density), - is_low_height, - disable_underspeed_handling); - if (_launchDetector.getLaunchDetected() < launch_detection_status_s::STATE_FLYING) { - // explicitly set idle throttle until motors are enabled - _att_sp.thrust_body[0] = _param_fw_thr_idle.get(); + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - } else { - _att_sp.thrust_body[0] = get_tecs_thrust(); - } + _ctrl_configuration_handler.setPitchMin(radians(_takeoff_pitch_min.get())); + _ctrl_configuration_handler.setThrottleMax(max_takeoff_throttle); + _ctrl_configuration_handler.setClimbRateTarget(_param_fw_t_clmb_max.get()); + _ctrl_configuration_handler.setDisableUnderspeedProtection(true); - float pitch_body = get_tecs_pitch(); - float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - - roll_body = constrainRollNearGround(roll_body, _current_altitude, _takeoff_ground_alt); - - Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + //float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw } else { + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = now; + fw_lateral_ctrl_sp.lateral_acceleration = 0.f; /* Tell the attitude controller to stop integrating while we are waiting for the launch */ - _att_sp.reset_integral = true; - - /* Set default roll and pitch setpoints during detection phase */ - float roll_body = 0.0f; - float yaw_body = _yaw; - _att_sp.thrust_body[0] = _param_fw_thr_idle.get(); - float pitch_body = radians(_takeoff_pitch_min.get()); - roll_body = constrainRollNearGround(roll_body, _current_altitude, _takeoff_ground_alt); - Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); + fixed_wing_longitudinal_setpoint_s long_control_sp{empty_longitudinal_control_setpoint}; + long_control_sp.timestamp = now; + long_control_sp.pitch_direct = radians(_takeoff_pitch_min.get()); + long_control_sp.throttle_direct = _param_fw_thr_idle.get(); + _longitudinal_ctrl_sp_pub.publish(long_control_sp); } launch_detection_status_s launch_detection_status; @@ -1746,20 +1264,10 @@ void FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, const float control_interval, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr) { - // first handle non-position things like airspeed and tecs settings const float airspeed_land = (_param_fw_lnd_airspd.get() > FLT_EPSILON) ? _param_fw_lnd_airspd.get() : - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); - float adjusted_min_airspeed = _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); - - if (airspeed_land < adjusted_min_airspeed) { - // adjust underspeed detection bounds for landing airspeed - _tecs.set_equivalent_airspeed_min(airspeed_land); - adjusted_min_airspeed = airspeed_land; - } - - float target_airspeed = adapt_airspeed_setpoint(control_interval, airspeed_land, adjusted_min_airspeed, - ground_speed); + _param_fw_airspd_min.get(); + _ctrl_configuration_handler.setEnforceLowHeightCondition(true); // now handle position const Vector2f local_position{_local_pos.x, _local_pos.y}; @@ -1807,8 +1315,6 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, // flare at the maximum of the altitude determined by the time before touchdown and a minimum flare altitude const float flare_rel_alt = math::max(_param_fw_lnd_fl_time.get() * _local_pos.vz, _param_fw_lnd_flalt.get()); - // During landing, enforce low-height flight conditions for tighter altitude control - const bool is_low_height = true; // the terrain estimate (if enabled) is always used to determine the flaring altitude if ((_current_altitude < terrain_alt + flare_rel_alt) || _flare_states.flaring) { @@ -1819,7 +1325,6 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, _flare_states.flaring = true; _flare_states.start_time = now; _flare_states.initial_height_rate_setpoint = -_local_pos.vz; - _flare_states.initial_throttle_setpoint = _att_sp.thrust_body[0]; events::send(events::ID("fixedwing_position_control_landing_flaring"), events::Log::Info, "Landing, flaring"); } @@ -1830,22 +1335,19 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, 1.0f); /* lateral guidance first, because npfg will adjust the airspeed setpoint if necessary */ - - // tune up the lateral position control guidance when on the ground - const float ground_roll_npfg_period = flare_ramp_interpolator * _param_rwto_npfg_period.get() + - (1.0f - flare_ramp_interpolator) * _param_npfg_period.get(); - _npfg.setPeriod(ground_roll_npfg_period); - const Vector2f local_approach_entrance = local_land_point - landing_approach_vector; - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateLine(local_approach_entrance, local_land_point, local_position, ground_speed, _wind_vel); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - float roll_body = getCorrectedNpfgRollSetpoint(); + const DirectionalGuidanceOutput sp = navigateLine(local_approach_entrance, local_land_point, local_position, + ground_speed, + _wind_vel); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = now; + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); - // use npfg's bearing to commanded course, controlled via yaw angle while on runway - float yaw_body = _npfg.getBearing(); + const float roll_wingtip_strike = getMaxRollAngleNearGround(_current_altitude, _takeoff_ground_alt); + _ctrl_configuration_handler.setLateralAccelMax(rollAngleToLateralAccel(roll_wingtip_strike)); /* longitudinal guidance */ @@ -1877,47 +1379,23 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, const float throttle_max = flare_ramp_interpolator_sqrt * _param_fw_thr_idle.get() + (1.0f - flare_ramp_interpolator_sqrt) * _param_fw_thr_max.get(); - const bool disable_underspeed_handling = true; - tecs_update_pitch_throttle(control_interval, - altitude_setpoint, - target_airspeed, - pitch_min_rad, - pitch_max_rad, - _param_fw_thr_idle.get(), - throttle_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height, - disable_underspeed_handling, - height_rate_setpoint); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = now, + .altitude = altitude_setpoint, + .height_rate = height_rate_setpoint, + .equivalent_airspeed = airspeed_land, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - /* set the attitude and throttle commands */ + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - // TECS has authority (though constrained) over pitch during flare, throttle is hard set to idle - float pitch_body = get_tecs_pitch(); - - roll_body = constrainRollNearGround(roll_body, _current_altitude, terrain_alt); - - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); - - // enable direct yaw control using rudder/wheel - _att_sp.fw_control_yaw_wheel = true; - - // XXX: hacky way to pass through manual nose-wheel incrementing. need to clean this interface. - if (_param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled) { - _att_sp.yaw_sp_move_rate = _manual_control_setpoint.yaw; - } - - // blend the height rate controlled throttle setpoints with initial throttle setting over the flare - // ramp time period to maintain throttle command continuity when switching from altitude to height rate - // control - const float blended_throttle = flare_ramp_interpolator * get_tecs_thrust() + (1.0f - flare_ramp_interpolator) * - _flare_states.initial_throttle_setpoint; - - _att_sp.thrust_body[0] = blended_throttle; + _ctrl_configuration_handler.setPitchMin(pitch_min_rad); + _ctrl_configuration_handler.setPitchMax(pitch_max_rad); + _ctrl_configuration_handler.setThrottleMax(throttle_max); + _ctrl_configuration_handler.setThrottleMin(_param_fw_thr_idle.get()); + _ctrl_configuration_handler.setDisableUnderspeedProtection(true); } else { @@ -1927,51 +1405,41 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, const Vector2f local_approach_entrance = local_land_point - landing_approach_vector; - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateLine(local_approach_entrance, local_land_point, local_position, ground_speed, _wind_vel); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - float roll_body = getCorrectedNpfgRollSetpoint(); + const DirectionalGuidanceOutput sp = navigateLine(local_approach_entrance, local_land_point, local_position, + ground_speed, + _wind_vel); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); + + _ctrl_configuration_handler.setLateralAccelMax(rollAngleToLateralAccel(getMaxRollAngleNearGround(_current_altitude, + terrain_alt))); /* longitudinal guidance */ - // open the desired max sink rate to encompass the glide slope if within the aircraft's performance limits + // Open the desired max sink rate to encompass the glide slope. // x/sqrt(x^2+1) = sin(arctan(x)) const float glide_slope_sink_rate = airspeed_land * glide_slope / sqrtf(glide_slope * glide_slope + 1.0f); - const float desired_max_sinkrate = math::min(math::max(glide_slope_sink_rate, _param_sinkrate_target.get()), - _param_fw_t_sink_max.get()); + const float desired_max_sinkrate = math::max(glide_slope_sink_rate, _param_sinkrate_target.get()); - tecs_update_pitch_throttle(control_interval, - altitude_setpoint, - target_airspeed, - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - _param_fw_thr_min.get(), - _param_fw_thr_max.get(), - desired_max_sinkrate, - _param_climbrate_target.get(), - is_low_height); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = altitude_setpoint, + .height_rate = NAN, + .equivalent_airspeed = airspeed_land, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - /* set the attitude and throttle commands */ + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - float pitch_body = get_tecs_pitch(); - - roll_body = constrainRollNearGround(roll_body, _current_altitude, terrain_alt); - - // yaw is not controlled in nominal flight - float yaw_body = _yaw; - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); - - // enable direct yaw control using rudder/wheel - _att_sp.fw_control_yaw_wheel = false; - - _att_sp.thrust_body[0] = (_landed) ? _param_fw_thr_idle.get() : get_tecs_thrust(); + _ctrl_configuration_handler.setThrottleMin(_param_fw_thr_idle.get()); + _ctrl_configuration_handler.setThrottleMax(_landed ? _param_fw_thr_idle.get() : NAN); + _ctrl_configuration_handler.setSinkRateTarget(desired_max_sinkrate); } - _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation - _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); _spoilers_setpoint = _param_fw_spoilers_lnd.get(); @@ -1989,19 +1457,10 @@ void FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, const float control_interval, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { - // first handle non-position things like airspeed and tecs settings const float airspeed_land = (_param_fw_lnd_airspd.get() > FLT_EPSILON) ? _param_fw_lnd_airspd.get() : - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); - float adjusted_min_airspeed = _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); + _param_fw_airspd_min.get(); - if (airspeed_land < adjusted_min_airspeed) { - // adjust underspeed detection bounds for landing airspeed - _tecs.set_equivalent_airspeed_min(airspeed_land); - adjusted_min_airspeed = airspeed_land; - } - - float target_airspeed = adapt_airspeed_setpoint(control_interval, airspeed_land, adjusted_min_airspeed, - ground_speed); + _ctrl_configuration_handler.setEnforceLowHeightCondition(true); const Vector2f local_position{_local_pos.x, _local_pos.y}; @@ -2026,14 +1485,6 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, loiter_radius = _param_nav_loiter_rad.get(); } - // During landing, enforce low-height flight conditions for tighter altitude control - const bool is_low_height = true; - - // the terrain estimate (if enabled) is always used to determine the flaring altitude - float roll_body; - float yaw_body; - float pitch_body; - if ((_current_altitude < terrain_alt + flare_rel_alt) || _flare_states.flaring) { // flare and land with minimal speed @@ -2042,7 +1493,6 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, _flare_states.flaring = true; _flare_states.start_time = now; _flare_states.initial_height_rate_setpoint = -_local_pos.vz; - _flare_states.initial_throttle_setpoint = _att_sp.thrust_body[0]; events::send(events::ID("fixedwing_position_control_landing_circle_flaring"), events::Log::Info, "Landing, flaring"); } @@ -2053,23 +1503,15 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, 1.0f); /* lateral guidance first, because npfg will adjust the airspeed setpoint if necessary */ + const DirectionalGuidanceOutput sp = navigateLoiter(local_landing_orbit_center, local_position, loiter_radius, + pos_sp_curr.loiter_direction_counter_clockwise, + ground_speed, _wind_vel); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = now; + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; - // tune up the lateral position control guidance when on the ground - const float ground_roll_npfg_period = flare_ramp_interpolator * _param_rwto_npfg_period.get() + - (1.0f - flare_ramp_interpolator) * _param_npfg_period.get(); - - _npfg.setPeriod(ground_roll_npfg_period); - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - - navigateLoiter(local_landing_orbit_center, local_position, loiter_radius, - pos_sp_curr.loiter_direction_counter_clockwise, - ground_speed, _wind_vel); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - roll_body = getCorrectedNpfgRollSetpoint(); - - yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); /* longitudinal guidance */ const float flare_ramp_interpolator_sqrt = sqrtf(flare_ramp_interpolator); @@ -2099,99 +1541,62 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, const float throttle_max = flare_ramp_interpolator_sqrt * _param_fw_thr_idle.get() + (1.0f - flare_ramp_interpolator_sqrt) * _param_fw_thr_max.get(); - const bool disable_underspeed_handling = true; + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = now, + .altitude = NAN, + .height_rate = height_rate_setpoint, + .equivalent_airspeed = airspeed_land, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - tecs_update_pitch_throttle(control_interval, - _current_altitude, // is not controlled, control descend rate - target_airspeed, - pitch_min_rad, - pitch_max_rad, - _param_fw_thr_idle.get(), - throttle_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height, - disable_underspeed_handling, - height_rate_setpoint); + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - /* set the attitude and throttle commands */ - - // TECS has authority (though constrained) over pitch during flare, throttle is hard set to idle - pitch_body = get_tecs_pitch(); - - // enable direct yaw control using rudder/wheel - _att_sp.fw_control_yaw_wheel = true; - - // XXX: hacky way to pass through manual nose-wheel incrementing. need to clean this interface. - if (_param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled) { - _att_sp.yaw_sp_move_rate = _manual_control_setpoint.yaw; - } - - // blend the height rate controlled throttle setpoints with initial throttle setting over the flare - // ramp time period to maintain throttle command continuity when switching from altitude to height rate - // control - const float blended_throttle = flare_ramp_interpolator * get_tecs_thrust() + (1.0f - flare_ramp_interpolator) * - _flare_states.initial_throttle_setpoint; - - _att_sp.thrust_body[0] = blended_throttle; + _ctrl_configuration_handler.setPitchMin(pitch_min_rad); + _ctrl_configuration_handler.setPitchMax(pitch_max_rad); + _ctrl_configuration_handler.setThrottleMax(throttle_max); + _ctrl_configuration_handler.setThrottleMin(_param_fw_thr_idle.get()); + _ctrl_configuration_handler.setDisableUnderspeedProtection(true); } else { // follow the glide slope + const DirectionalGuidanceOutput sp = navigateLoiter(local_landing_orbit_center, local_position, loiter_radius, + pos_sp_curr.loiter_direction_counter_clockwise, + ground_speed, _wind_vel); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = now; + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; - /* lateral guidance */ - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - - navigateLoiter(local_landing_orbit_center, local_position, loiter_radius, - pos_sp_curr.loiter_direction_counter_clockwise, - ground_speed, _wind_vel); - target_airspeed = _npfg.getAirspeedRef() / _eas2tas; - roll_body = getCorrectedNpfgRollSetpoint(); + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); /* longitudinal guidance */ - // open the desired max sink rate to encompass the glide slope if within the aircraft's performance limits + // Open the desired max sink rate to encompass the glide slope. // x/sqrt(x^2+1) = sin(arctan(x)) const float glide_slope = math::radians(_param_fw_lnd_ang.get()); const float glide_slope_sink_rate = airspeed_land * glide_slope / sqrtf(glide_slope * glide_slope + 1.0f); - const float desired_max_sinkrate = math::min(math::max(glide_slope_sink_rate, _param_sinkrate_target.get()), - _param_fw_t_sink_max.get()); - const bool disable_underspeed_handling = false; + const float desired_max_sinkrate = math::max(glide_slope_sink_rate, _param_sinkrate_target.get()); - tecs_update_pitch_throttle(control_interval, - _current_altitude, // is not controlled, control descend rate - target_airspeed, - radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get()), - _param_fw_thr_min.get(), - _param_fw_thr_max.get(), - desired_max_sinkrate, - _param_climbrate_target.get(), - is_low_height, - disable_underspeed_handling, - -glide_slope_sink_rate); // heightrate = -sinkrate + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = now, + .altitude = NAN, + .height_rate = -glide_slope_sink_rate, + .equivalent_airspeed = airspeed_land, + .pitch_direct = NAN, + .throttle_direct = NAN + }; - /* set the attitude and throttle commands */ + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - pitch_body = get_tecs_pitch(); - - // yaw is not controlled in nominal flight - yaw_body = _yaw; - - // enable direct yaw control using rudder/wheel - _att_sp.fw_control_yaw_wheel = false; - - _att_sp.thrust_body[0] = (_landed) ? _param_fw_thr_idle.get() : get_tecs_thrust(); + _ctrl_configuration_handler.setThrottleMin(_param_fw_thr_idle.get()); + _ctrl_configuration_handler.setThrottleMax(_landed ? _param_fw_thr_idle.get() : NAN); + _ctrl_configuration_handler.setSinkRateTarget(desired_max_sinkrate); } - _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); // reset after TECS calculation - - roll_body = constrainRollNearGround(roll_body, _current_altitude, terrain_alt); - - Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); - + _ctrl_configuration_handler.setLateralAccelMax(rollAngleToLateralAccel(getMaxRollAngleNearGround(_current_altitude, + terrain_alt))); _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); _spoilers_setpoint = _param_fw_spoilers_lnd.get(); @@ -2210,66 +1615,58 @@ FixedwingPositionControl::control_manual_altitude(const float control_interval, { updateManualTakeoffStatus(); - const float calibrated_airspeed_sp = adapt_airspeed_setpoint(control_interval, get_manual_airspeed_setpoint(), - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), ground_speed, !_completed_manual_takeoff); const float height_rate_sp = getManualHeightRateSetpoint(); // TECS may try to pitch down to gain airspeed if we underspeed, constrain the pitch when underspeeding if we are // just passed launch - const float min_pitch = (_completed_manual_takeoff) ? radians(_param_fw_p_lim_min.get()) : + const float min_pitch = (_completed_manual_takeoff) ? NAN : MIN_PITCH_DURING_MANUAL_TAKEOFF; - float throttle_max = _param_fw_thr_max.get(); + float throttle_max = NAN; // enable the operator to kill the throttle on ground if (_landed && (_manual_control_setpoint_for_airspeed < THROTTLE_THRESH)) { throttle_max = 0.0f; } + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = NAN, + .height_rate = height_rate_sp, + .equivalent_airspeed = get_manual_airspeed_setpoint(), + .pitch_direct = NAN, + .throttle_direct = NAN + }; - const bool is_low_height = checkLowHeightConditions(); + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - const bool disable_underspeed_handling = false; + _ctrl_configuration_handler.setPitchMin(min_pitch); + _ctrl_configuration_handler.setThrottleMax(throttle_max); - tecs_update_pitch_throttle(control_interval, - _current_altitude, - calibrated_airspeed_sp, - min_pitch, - radians(_param_fw_p_lim_max.get()), - _param_fw_thr_min.get(), - throttle_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height, - disable_underspeed_handling, - height_rate_sp); - - float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); - float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - - _att_sp.thrust_body[0] = min(get_tecs_thrust(), throttle_max); - const float pitch_body = get_tecs_pitch(); - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); + const float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); + const DirectionalGuidanceOutput sp = {.course_setpoint = NAN, .lateral_acceleration_feedforward = rollAngleToLateralAccel(roll_body)}; + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); } void -FixedwingPositionControl::control_manual_position(const float control_interval, const Vector2d &curr_pos, +FixedwingPositionControl::control_manual_position(const hrt_abstime now, const float control_interval, + const Vector2d &curr_pos, const Vector2f &ground_speed) { updateManualTakeoffStatus(); - float calibrated_airspeed_sp = adapt_airspeed_setpoint(control_interval, get_manual_airspeed_setpoint(), - _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()), ground_speed, !_completed_manual_takeoff); const float height_rate_sp = getManualHeightRateSetpoint(); // TECS may try to pitch down to gain airspeed if we underspeed, constrain the pitch when underspeeding if we are // just passed launch - const float min_pitch = (_completed_manual_takeoff) ? radians(_param_fw_p_lim_min.get()) : + const float min_pitch = (_completed_manual_takeoff) ? NAN : MIN_PITCH_DURING_MANUAL_TAKEOFF; - float throttle_max = _param_fw_thr_max.get(); + float throttle_max = NAN; // enable the operator to kill the throttle on ground if (_landed && (_manual_control_setpoint_for_airspeed < THROTTLE_THRESH)) { @@ -2277,14 +1674,9 @@ FixedwingPositionControl::control_manual_position(const float control_interval, } if (_local_pos.xy_reset_counter != _xy_reset_counter) { - _time_last_xy_reset = _local_pos.timestamp; + _time_last_xy_reset = now; } - Eulerf current_setpoint(Quatf(_att_sp.q_d)); - float yaw_body = current_setpoint.psi(); - float roll_body = current_setpoint.phi(); - float pitch_body = current_setpoint.theta(); - /* heading control */ // TODO: either make it course hold (easier) or a real heading hold (minus all the complexity here) if (fabsf(_manual_control_setpoint.roll) < HDG_HOLD_MAN_INPUT_THRESH && @@ -2306,7 +1698,7 @@ FixedwingPositionControl::control_manual_position(const float control_interval, if (_yaw_lock_engaged) { - Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; + const Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; if (!_hdg_hold_enabled) { // just switched back from non heading-hold to heading hold @@ -2318,37 +1710,34 @@ FixedwingPositionControl::control_manual_position(const float control_interval, // if there's a reset-by-fusion, the ekf needs some time to converge, // therefore we go into track holiding for 2 seconds - if (_local_pos.timestamp - _time_last_xy_reset < 2_s) { + if (now - _time_last_xy_reset < 2_s) { _hdg_hold_position = curr_pos_local; } - _npfg.setAirspeedNom(calibrated_airspeed_sp * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - navigateLine(_hdg_hold_position, _hdg_hold_yaw, curr_pos_local, ground_speed, _wind_vel); - roll_body = getCorrectedNpfgRollSetpoint(); - calibrated_airspeed_sp = _npfg.getAirspeedRef() / _eas2tas; + const DirectionalGuidanceOutput sp = navigateLine(_hdg_hold_position, _hdg_hold_yaw, curr_pos_local, ground_speed, + _wind_vel); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = now; + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; - yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); } } - const bool is_low_height = checkLowHeightConditions(); + const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { + .timestamp = hrt_absolute_time(), + .altitude = NAN, + .height_rate = height_rate_sp, + .equivalent_airspeed = get_manual_airspeed_setpoint(), + .pitch_direct = NAN, + .throttle_direct = NAN + }; - const bool disable_underspeed_handling = false; + _longitudinal_ctrl_sp_pub.publish(fw_longitudinal_control_sp); - - tecs_update_pitch_throttle(control_interval, - _current_altitude, // TODO: check if this is really what we want.. or if we want to lock the altitude. - calibrated_airspeed_sp, - min_pitch, - radians(_param_fw_p_lim_max.get()), - _param_fw_thr_min.get(), - throttle_max, - _param_sinkrate_target.get(), - _param_climbrate_target.get(), - is_low_height, - disable_underspeed_handling, - height_rate_sp); + _ctrl_configuration_handler.setPitchMin(min_pitch); + _ctrl_configuration_handler.setThrottleMax(throttle_max); if (!_yaw_lock_engaged || fabsf(_manual_control_setpoint.roll) >= HDG_HOLD_MAN_INPUT_THRESH || fabsf(_manual_control_setpoint.yaw) >= HDG_HOLD_MAN_INPUT_THRESH) { @@ -2356,16 +1745,17 @@ FixedwingPositionControl::control_manual_position(const float control_interval, _hdg_hold_enabled = false; _yaw_lock_engaged = false; - roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); - yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw + const float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.lateral_acceleration = rollAngleToLateralAccel(roll_body); + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); } +} - _att_sp.thrust_body[0] = min(get_tecs_thrust(), throttle_max); - - pitch_body = get_tecs_pitch(); - - Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); +float FixedwingPositionControl::rollAngleToLateralAccel(float roll_body) const +{ + return tanf(roll_body) * CONSTANTS_ONE_G; } void FixedwingPositionControl::control_backtransition_heading_hold() @@ -2374,34 +1764,10 @@ void FixedwingPositionControl::control_backtransition_heading_hold() _backtrans_heading = _local_pos.heading; } - float true_airspeed = _airspeed_eas * _eas2tas; - - if (!_airspeed_valid) { - true_airspeed = _performance_model.getCalibratedTrimAirspeed() * _eas2tas; - } - - // we can achieve heading control by setting airspeed and groundspeed vector equal - const Vector2f airspeed_vector = Vector2f(cosf(_local_pos.heading), sinf(_local_pos.heading)) * true_airspeed; - const Vector2f &ground_speed = airspeed_vector; - - _npfg.setAirspeedNom(_performance_model.getCalibratedTrimAirspeed() * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - - Vector2f virtual_target_point = Vector2f(cosf(_backtrans_heading), sinf(_backtrans_heading)) * HDG_HOLD_DIST_NEXT; - - navigateLine(Vector2f(0.f, 0.f), virtual_target_point, Vector2f(0.f, 0.f), ground_speed, Vector2f(0.f, 0.f)); - - const float roll_body = getCorrectedNpfgRollSetpoint(); - - const float yaw_body = _backtrans_heading; - - // these values are overriden by transition logic - _att_sp.thrust_body[0] = _param_fw_thr_min.get(); - const float pitch_body = 0.0f; - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); - + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.airspeed_direction = _backtrans_heading; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); } void FixedwingPositionControl::control_backtransition_line_follow(const Vector2f &ground_speed, @@ -2410,47 +1776,23 @@ void FixedwingPositionControl::control_backtransition_line_follow(const Vector2f Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; Vector2f curr_wp_local = _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon); - _npfg.setAirspeedNom(_performance_model.getCalibratedTrimAirspeed() * _eas2tas); - _npfg.setAirspeedMax(_performance_model.getMaximumCalibratedAirspeed() * _eas2tas); - // Set the position where the backtransition started the first ime we pass through here. // Will get reset if not in transition anymore. if (!_lpos_where_backtrans_started.isAllFinite()) { _lpos_where_backtrans_started = curr_pos_local; } - navigateLine(_lpos_where_backtrans_started, curr_wp_local, curr_pos_local, ground_speed, _wind_vel); - const float roll_body = getCorrectedNpfgRollSetpoint(); + DirectionalGuidanceOutput sp = {.course_setpoint = NAN, .lateral_acceleration_feedforward = 0.f}; - const float yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw - - // these values are overriden by transition logic - _att_sp.thrust_body[0] = _param_fw_thr_min.get(); - const float pitch_body = 0.0f; - - const Quatf attitude_setpoint(Eulerf(roll_body, pitch_body, yaw_body)); - attitude_setpoint.copyTo(_att_sp.q_d); -} -float -FixedwingPositionControl::get_tecs_pitch() -{ - if (_tecs_is_running) { - return _tecs.get_pitch_setpoint() + radians(_param_fw_psp_off.get()); + if (_control_mode.flag_control_position_enabled) { + sp = navigateLine(_lpos_where_backtrans_started, curr_wp_local, curr_pos_local, ground_speed, _wind_vel); } - // return level flight pitch offset to prevent stale tecs state when it's not running - return radians(_param_fw_psp_off.get()); -} - -float -FixedwingPositionControl::get_tecs_thrust() -{ - if (_tecs_is_running) { - return min(_tecs.get_throttle_setpoint(), 1.f); - } - - // return 0 to prevent stale tecs state when it's not running - return 0.0f; + fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; + fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); + fw_lateral_ctrl_sp.course = sp.course_setpoint; + fw_lateral_ctrl_sp.lateral_acceleration = sp.lateral_acceleration_feedforward; + _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); } void @@ -2464,13 +1806,30 @@ FixedwingPositionControl::Run() perf_begin(_loop_perf); - /* only run controller if position changed */ + if (_vehicle_status_sub.updated()) { - if (_local_pos_sub.update(&_local_pos)) { + if (_vehicle_status_sub.update(&_vehicle_status)) { + _nav_state = _vehicle_status.nav_state; + } + } - const float control_interval = math::constrain((_local_pos.timestamp - _last_time_position_control_called) * 1e-6f, + /* only run controller if position changed and we are not running an external mode*/ + + const bool is_external_nav_state = (_nav_state >= vehicle_status_s::NAVIGATION_STATE_EXTERNAL1) + && (_nav_state <= vehicle_status_s::NAVIGATION_STATE_EXTERNAL8); + + if (is_external_nav_state) { + // this will cause the configuration handler to publish immediately the next time an internal flight + // mode is active + _ctrl_configuration_handler.resetLastPublishTime(); + + } else if (_local_pos_sub.update(&_local_pos)) { + + const hrt_abstime now = _local_pos.timestamp; + + const float control_interval = math::constrain((now - _last_time_position_control_called) * 1e-6f, MIN_AUTO_TIMESTEP, MAX_AUTO_TIMESTEP); - _last_time_position_control_called = _local_pos.timestamp; + _last_time_position_control_called = now; // check for parameter updates if (_parameter_update_sub.updated()) { @@ -2500,11 +1859,6 @@ FixedwingPositionControl::Run() // handle estimator reset events. we only adjust setpoins for manual modes if (_control_mode.flag_control_manual_enabled) { - if (_control_mode.flag_control_altitude_enabled && _local_pos.z_reset_counter != _z_reset_counter) { - // make TECS accept step in altitude and demanded altitude - _tecs.handle_alt_step(_current_altitude, -_local_pos.vz); - } - // adjust navigation waypoints in position control mode if (_control_mode.flag_control_altitude_enabled && _control_mode.flag_control_velocity_enabled && _local_pos.xy_reset_counter != _xy_reset_counter) { @@ -2612,15 +1966,7 @@ FixedwingPositionControl::Run() vehicle_attitude_poll(); vehicle_command_poll(); vehicle_control_mode_poll(); - wind_poll(); - - vehicle_air_data_s air_data; - - if (_vehicle_air_data_sub.update(&air_data)) { - _air_density = PX4_ISFINITE(air_data.rho) ? air_data.rho : _air_density; - _tecs.set_max_climb_rate(_performance_model.getMaximumClimbRate(_air_density)); - _tecs.set_min_sink_rate(_performance_model.getMinimumSinkRate(_air_density)); - } + wind_poll(now); if (_vehicle_land_detected_sub.updated()) { vehicle_land_detected_s vehicle_land_detected; @@ -2630,38 +1976,31 @@ FixedwingPositionControl::Run() } } - if (_vehicle_status_sub.update(&_vehicle_status)) { - if (!_vehicle_status.in_transition_mode) { - // reset position of backtransition start if not in transition - _lpos_where_backtrans_started = Vector2f(NAN, NAN); - _backtrans_heading = NAN; - } + if (!_vehicle_status.in_transition_mode) { + // reset position of backtransition start if not in transition + _lpos_where_backtrans_started = Vector2f(NAN, NAN); + _backtrans_heading = NAN; } + Vector2d curr_pos(_current_latitude, _current_longitude); Vector2f ground_speed(_local_pos.vx, _local_pos.vy); - set_control_mode_current(_local_pos.timestamp); + set_control_mode_current(now); - update_in_air_states(_local_pos.timestamp); + update_in_air_states(now); // restore nominal TECS parameters in case changed intermittently (e.g. in landing handling) - _tecs.set_speed_weight(_param_fw_t_spdweight.get()); // restore lateral-directional guidance parameters (changed in takeoff mode) - _npfg.setPeriod(_param_npfg_period.get()); - - _att_sp.reset_integral = false; + _directional_guidance.setPeriod(_param_npfg_period.get()); // by default no flaps/spoilers, is overwritten below in certain modes _flaps_setpoint = 0.f; _spoilers_setpoint = 0.f; - // reset flight phase estimate - _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_UNKNOWN; - - // by default we don't want yaw to be contoller directly with rudder - _att_sp.fw_control_yaw_wheel = false; + // by default set speed weight to the param value, can be overwritten inside the methods below + _ctrl_configuration_handler.setSpeedWeight(_param_t_spdweight.get()); // default to zero - is used (IN A HACKY WAY) to pass direct nose wheel steering via yaw stick to the actuators during auto takeoff _att_sp.yaw_sp_move_rate = 0.0f; @@ -2686,23 +2025,23 @@ FixedwingPositionControl::Run() } case FW_POSCTRL_MODE_AUTO_ALTITUDE: { - control_auto_fixed_bank_alt_hold(control_interval); + control_auto_fixed_bank_alt_hold(); break; } case FW_POSCTRL_MODE_AUTO_CLIMBRATE: { - control_auto_descend(control_interval); + control_auto_descend(); break; } case FW_POSCTRL_MODE_AUTO_LANDING_STRAIGHT: { - control_auto_landing_straight(_local_pos.timestamp, control_interval, ground_speed, _pos_sp_triplet.previous, + control_auto_landing_straight(now, control_interval, ground_speed, _pos_sp_triplet.previous, _pos_sp_triplet.current); break; } case FW_POSCTRL_MODE_AUTO_LANDING_CIRCULAR: { - control_auto_landing_circular(_local_pos.timestamp, control_interval, ground_speed, _pos_sp_triplet.current); + control_auto_landing_circular(now, control_interval, ground_speed, _pos_sp_triplet.current); break; } @@ -2712,12 +2051,12 @@ FixedwingPositionControl::Run() } case FW_POSCTRL_MODE_AUTO_TAKEOFF: { - control_auto_takeoff(_local_pos.timestamp, control_interval, curr_pos, ground_speed, _pos_sp_triplet.current); + control_auto_takeoff(now, control_interval, curr_pos, ground_speed, _pos_sp_triplet.current); break; } case FW_POSCTRL_MODE_MANUAL_POSITION: { - control_manual_position(control_interval, curr_pos, ground_speed); + control_manual_position(now, control_interval, curr_pos, ground_speed); break; } @@ -2727,7 +2066,6 @@ FixedwingPositionControl::Run() } case FW_POSCTRL_MODE_OTHER: { - _att_sp.thrust_body[0] = min(_att_sp.thrust_body[0], _param_fw_thr_max.get()); break; } @@ -2742,52 +2080,16 @@ FixedwingPositionControl::Run() } } - if (_control_mode_current != FW_POSCTRL_MODE_OTHER) { - Eulerf attitude_setpoint(Quatf(_att_sp.q_d)); - float roll_body = attitude_setpoint.phi(); - float pitch_body = attitude_setpoint.theta(); - float yaw_body = attitude_setpoint.psi(); - - if (_control_mode.flag_control_manual_enabled) { - roll_body = constrain(roll_body, -radians(_param_fw_r_lim.get()), - radians(_param_fw_r_lim.get())); - pitch_body = constrain(pitch_body, radians(_param_fw_p_lim_min.get()), - radians(_param_fw_p_lim_max.get())); - } - - if (_control_mode.flag_control_position_enabled || - _control_mode.flag_control_velocity_enabled || - _control_mode.flag_control_acceleration_enabled || - _control_mode.flag_control_altitude_enabled || - _control_mode.flag_control_climb_rate_enabled) { - - // roll slew rate - roll_body = _roll_slew_rate.update(roll_body, control_interval); - - const Quatf q(Eulerf(roll_body, pitch_body, yaw_body)); - q.copyTo(_att_sp.q_d); - - _att_sp.timestamp = hrt_absolute_time(); - _attitude_sp_pub.publish(_att_sp); - - // only publish status in full FW mode - if (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING - || _vehicle_status.in_transition_mode) { - status_publish(); - - } - } - - } else { - _roll_slew_rate.setForcedValue(_roll); + _ctrl_configuration_handler.update(now); } + // only publish status in full FW mode + if (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING + || _vehicle_status.in_transition_mode) { + publish_lateral_guidance_status(now); - - // Publish estimate of level flight - _flight_phase_estimation_pub.get().timestamp = hrt_absolute_time(); - _flight_phase_estimation_pub.update(); + } // if there's any change in landing gear setpoint publish it if (_new_landing_gear_position != old_landing_gear_position @@ -2795,7 +2097,7 @@ FixedwingPositionControl::Run() landing_gear_s landing_gear = {}; landing_gear.landing_gear = _new_landing_gear_position; - landing_gear.timestamp = hrt_absolute_time(); + landing_gear.timestamp = now; _landing_gear_pub.publish(landing_gear); } @@ -2804,16 +2106,15 @@ FixedwingPositionControl::Run() && _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { normalized_unsigned_setpoint_s flaps_setpoint; flaps_setpoint.normalized_setpoint = _flaps_setpoint; - flaps_setpoint.timestamp = hrt_absolute_time(); + flaps_setpoint.timestamp = now; _flaps_setpoint_pub.publish(flaps_setpoint); normalized_unsigned_setpoint_s spoilers_setpoint; spoilers_setpoint.normalized_setpoint = _spoilers_setpoint; - spoilers_setpoint.timestamp = hrt_absolute_time(); + spoilers_setpoint.timestamp = now; _spoilers_setpoint_pub.publish(spoilers_setpoint); } - _z_reset_counter = _local_pos.z_reset_counter; _xy_reset_counter = _local_pos.xy_reset_counter; perf_end(_loop_perf); @@ -2844,86 +2145,14 @@ FixedwingPositionControl::reset_landing_state() _last_time_terrain_alt_was_valid = 0; // reset abort land, unless loitering after an abort - if (_landing_abort_status && (_pos_sp_triplet.current.type != position_setpoint_s::SETPOINT_TYPE_LOITER)) { + if ((_landing_abort_status && (_pos_sp_triplet.current.type != position_setpoint_s::SETPOINT_TYPE_LOITER)) || + (_landing_abort_status && _param_fw_lnd_abort.get() == 0)) { updateLandingAbortStatus(position_controller_landing_status_s::NOT_ABORTED); } } -void -FixedwingPositionControl::tecs_update_pitch_throttle(const float control_interval, float alt_sp, float airspeed_sp, - float pitch_min_rad, float pitch_max_rad, float throttle_min, float throttle_max, - const float desired_max_sinkrate, const float desired_max_climbrate, const bool is_low_height, - bool disable_underspeed_detection, float hgt_rate_sp) -{ - // do not run TECS if vehicle is a VTOL and we are in rotary wing mode or in transition - if (_vehicle_status.is_vtol && (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING - || _vehicle_status.in_transition_mode)) { - _tecs_is_running = false; - return; - - } else { - _tecs_is_running = true; - } - - /* update TECS vehicle state estimates */ - const float throttle_trim_compensated = _performance_model.getTrimThrottle(throttle_min, - throttle_max, airspeed_sp, _air_density); - - /* No underspeed protection in landing mode */ - _tecs.set_detect_underspeed_enabled(!disable_underspeed_detection); - - updateTECSAltitudeTimeConstant(is_low_height, control_interval); - - // HOTFIX: the airspeed rate estimate using acceleration in body-forward direction has shown to lead to high biases - // when flying tight turns. It's in this case much safer to just set the estimated airspeed rate to 0. - const float airspeed_rate_estimate = 0.f; - - _tecs.update(_pitch - radians(_param_fw_psp_off.get()), - _current_altitude, - alt_sp, - airspeed_sp, - _airspeed_eas, - _eas2tas, - throttle_min, - throttle_max, - throttle_trim_compensated, - pitch_min_rad - radians(_param_fw_psp_off.get()), - pitch_max_rad - radians(_param_fw_psp_off.get()), - desired_max_climbrate, - desired_max_sinkrate, - airspeed_rate_estimate, - -_local_pos.vz, - hgt_rate_sp); - - tecs_status_publish(alt_sp, airspeed_sp, airspeed_rate_estimate, throttle_trim_compensated); - - if (_tecs_is_running && !_vehicle_status.in_transition_mode - && (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING)) { - const TECS::DebugOutput &tecs_output{_tecs.getStatus()}; - - // Check level flight: the height rate setpoint is not set or set to 0 and we are close to the target altitude and target altitude is not moving - if ((fabsf(tecs_output.height_rate_reference) < MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT) && - fabsf(_current_altitude - tecs_output.altitude_reference) < _param_nav_fw_alt_rad.get()) { - _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_LEVEL; - - } else if (((tecs_output.altitude_reference - _current_altitude) >= _param_nav_fw_alt_rad.get()) || - (tecs_output.height_rate_reference >= MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT)) { - _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_CLIMB; - - } else if (((_current_altitude - tecs_output.altitude_reference) >= _param_nav_fw_alt_rad.get()) || - (tecs_output.height_rate_reference <= -MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT)) { - _flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_DESCEND; - - } else { - //We can't infer the flight phase , do nothing, estimation is reset at each step - } - } -} - -float -FixedwingPositionControl::constrainRollNearGround(const float roll_setpoint, const float altitude, - const float terrain_altitude) const +float FixedwingPositionControl::getMaxRollAngleNearGround(const float altitude, const float terrain_altitude) const { // we want the wings level when at the wing height above ground const float height_above_ground = math::max(altitude - (terrain_altitude + _param_fw_wing_height.get()), 0.0f); @@ -2933,11 +2162,12 @@ FixedwingPositionControl::constrainRollNearGround(const float roll_setpoint, con // d(roll strike)/d(height) = 2 / span / cos(2 * height / span) // d(roll strike)/d(height) (@height=0) = 2 / span // roll strike ~= 2 * height / span - const float roll_wingtip_strike = 2.0f * height_above_ground / _param_fw_wing_span.get(); - return math::constrain(roll_setpoint, -roll_wingtip_strike, roll_wingtip_strike); + return math::constrain(2.f * height_above_ground / _param_fw_wing_span.get(), 0.f, + math::radians(_param_fw_r_lim.get())); } + void FixedwingPositionControl::initializeAutoLanding(const hrt_abstime &now, const position_setpoint_s &pos_sp_prev, const float land_point_altitude, const Vector2f &local_position, const Vector2f &local_land_point) @@ -2997,27 +2227,6 @@ FixedwingPositionControl::initializeAutoLanding(const hrt_abstime &now, const po } } -bool FixedwingPositionControl::checkLowHeightConditions() -{ - // Are conditions for low-height - return _param_fw_t_thr_low_hgt.get() >= 0.f && _local_pos.dist_bottom_valid - && _local_pos.dist_bottom < _param_fw_t_thr_low_hgt.get(); -} - -void FixedwingPositionControl::updateTECSAltitudeTimeConstant(const bool is_low_height, const float dt) -{ - // Target time constant for the TECS altitude tracker - float alt_tracking_tc = _param_fw_t_h_error_tc.get(); - - if (is_low_height) { - // If low-height conditions satisfied, compute target time constant for altitude tracking - alt_tracking_tc *= _param_fw_thrtc_sc.get(); - } - - _tecs_alt_time_const_slew_rate.update(alt_tracking_tc, dt); - _tecs.set_altitude_error_time_constant(_tecs_alt_time_const_slew_rate.getState()); -} - Vector2f FixedwingPositionControl::calculateTouchdownPosition(const float control_interval, const Vector2f &local_land_position) { @@ -3030,8 +2239,8 @@ FixedwingPositionControl::calculateTouchdownPosition(const float control_interva _manual_control_setpoint.yaw); _lateral_touchdown_position_offset += (_manual_control_setpoint.yaw - signed_deadzone_threshold) * MAX_TOUCHDOWN_POSITION_NUDGE_RATE * control_interval; - _lateral_touchdown_position_offset = math::constrain(_lateral_touchdown_position_offset, -_param_fw_lnd_td_off.get(), - _param_fw_lnd_td_off.get()); + _lateral_touchdown_position_offset = math::constrain(_lateral_touchdown_position_offset, -_param_fw_lnd_td_off.get(), + _param_fw_lnd_td_off.get()); } const Vector2f approach_unit_vector = -_landing_approach_entrance_offset_vector.unit_or_zero(); @@ -3137,9 +2346,6 @@ void FixedwingPositionControl::publishLocalPositionSetpoint(const position_setpo local_position_setpoint.acceleration[0] = NAN; local_position_setpoint.acceleration[1] = NAN; local_position_setpoint.acceleration[2] = NAN; - local_position_setpoint.thrust[0] = _att_sp.thrust_body[0]; - local_position_setpoint.thrust[1] = _att_sp.thrust_body[1]; - local_position_setpoint.thrust[2] = _att_sp.thrust_body[2]; _local_pos_sp_pub.publish(local_position_setpoint); } @@ -3162,7 +2368,8 @@ void FixedwingPositionControl::publishOrbitStatus(const position_setpoint_s pos_ _orbit_status_pub.publish(orbit_status); } -void FixedwingPositionControl::navigateWaypoints(const Vector2f &start_waypoint, const Vector2f &end_waypoint, +DirectionalGuidanceOutput FixedwingPositionControl::navigateWaypoints(const Vector2f &start_waypoint, + const Vector2f &end_waypoint, const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { const Vector2f start_waypoint_to_end_waypoint = end_waypoint - start_waypoint; @@ -3172,15 +2379,13 @@ void FixedwingPositionControl::navigateWaypoints(const Vector2f &start_waypoint, if (start_waypoint_to_end_waypoint.norm() < FLT_EPSILON) { // degenerate case: the waypoints are on top of each other, this should only happen when someone uses this // method incorrectly. just as a safe guard, call the singular waypoint navigation method. - navigateWaypoint(end_waypoint, vehicle_pos, ground_vel, wind_vel); - return; + return navigateWaypoint(end_waypoint, vehicle_pos, ground_vel, wind_vel); } if ((start_waypoint_to_end_waypoint.dot(start_waypoint_to_vehicle) < -FLT_EPSILON) - && (start_waypoint_to_vehicle.norm() > _npfg.switchDistance(500.0f))) { + && (start_waypoint_to_vehicle.norm() > _directional_guidance.switchDistance(500.0f))) { // we are in front of the start waypoint, fly directly to it until we are within switch distance - navigateWaypoint(start_waypoint, vehicle_pos, ground_vel, wind_vel); - return; + return navigateWaypoint(start_waypoint, vehicle_pos, ground_vel, wind_vel); } if (start_waypoint_to_end_waypoint.dot(end_waypoint_to_vehicle) > FLT_EPSILON) { @@ -3189,42 +2394,43 @@ void FixedwingPositionControl::navigateWaypoints(const Vector2f &start_waypoint, // end waypoint. however this included here as a safety precaution if any navigator (module) switch condition // is missed for any reason. in the future this logic should all be handled in one place in a dedicated // flight mode state machine. - navigateWaypoint(end_waypoint, vehicle_pos, ground_vel, wind_vel); - return; + return navigateWaypoint(end_waypoint, vehicle_pos, ground_vel, wind_vel); } // follow the line segment between the start and end waypoints - navigateLine(start_waypoint, end_waypoint, vehicle_pos, ground_vel, wind_vel); + return navigateLine(start_waypoint, end_waypoint, vehicle_pos, ground_vel, wind_vel); } -void FixedwingPositionControl::navigateWaypoint(const Vector2f &waypoint_pos, const Vector2f &vehicle_pos, +DirectionalGuidanceOutput FixedwingPositionControl::navigateWaypoint(const Vector2f &waypoint_pos, + const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { const Vector2f vehicle_to_waypoint = waypoint_pos - vehicle_pos; if (vehicle_to_waypoint.norm() < FLT_EPSILON) { // degenerate case: the vehicle is on top of the single waypoint. (can happen). maintain the last npfg command. - return; + return DirectionalGuidanceOutput{}; } const Vector2f unit_path_tangent = vehicle_to_waypoint.normalized(); _closest_point_on_path = waypoint_pos; const float path_curvature = 0.f; - _npfg.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, _closest_point_on_path, path_curvature); + DirectionalGuidanceOutput sp = _directional_guidance.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, + _closest_point_on_path, path_curvature); - // for logging - note we are abusing path tangent vs bearing definitions here. npfg interfaces need to be refined. - _target_bearing = atan2f(unit_path_tangent(1), unit_path_tangent(0)); + return sp; } -void FixedwingPositionControl::navigateLine(const Vector2f &point_on_line_1, const Vector2f &point_on_line_2, +DirectionalGuidanceOutput FixedwingPositionControl::navigateLine(const Vector2f &point_on_line_1, + const Vector2f &point_on_line_2, const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { const Vector2f line_segment = point_on_line_2 - point_on_line_1; if (line_segment.norm() <= FLT_EPSILON) { // degenerate case: line segment has zero length. maintain the last npfg command. - return; + return DirectionalGuidanceOutput{}; } const Vector2f unit_path_tangent = line_segment.normalized(); @@ -3233,13 +2439,15 @@ void FixedwingPositionControl::navigateLine(const Vector2f &point_on_line_1, con _closest_point_on_path = point_on_line_1 + point_1_to_vehicle.dot(unit_path_tangent) * unit_path_tangent; const float path_curvature = 0.f; - _npfg.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, _closest_point_on_path, path_curvature); + const DirectionalGuidanceOutput sp = _directional_guidance.guideToPath(vehicle_pos, ground_vel, wind_vel, + unit_path_tangent, + _closest_point_on_path, path_curvature); - // for logging - note we are abusing path tangent vs bearing definitions here. npfg interfaces need to be refined. - _target_bearing = atan2f(unit_path_tangent(1), unit_path_tangent(0)); + return sp; } -void FixedwingPositionControl::navigateLine(const Vector2f &point_on_line, const float line_bearing, +DirectionalGuidanceOutput FixedwingPositionControl::navigateLine(const Vector2f &point_on_line, + const float line_bearing, const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { const Vector2f unit_path_tangent{cosf(line_bearing), sinf(line_bearing)}; @@ -3248,13 +2456,15 @@ void FixedwingPositionControl::navigateLine(const Vector2f &point_on_line, const _closest_point_on_path = point_on_line + point_on_line_to_vehicle.dot(unit_path_tangent) * unit_path_tangent; const float path_curvature = 0.f; - _npfg.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, _closest_point_on_path, path_curvature); + const DirectionalGuidanceOutput sp = _directional_guidance.guideToPath(vehicle_pos, ground_vel, wind_vel, + unit_path_tangent, + _closest_point_on_path, path_curvature); - // for logging - note we are abusing path tangent vs bearing definitions here. npfg interfaces need to be refined. - _target_bearing = line_bearing; + return sp; } -void FixedwingPositionControl::navigateLoiter(const Vector2f &loiter_center, const Vector2f &vehicle_pos, +DirectionalGuidanceOutput FixedwingPositionControl::navigateLoiter(const Vector2f &loiter_center, + const Vector2f &vehicle_pos, float radius, bool loiter_direction_counter_clockwise, const Vector2f &ground_vel, const Vector2f &wind_vel) { const float loiter_direction_multiplier = loiter_direction_counter_clockwise ? -1.f : 1.f; @@ -3286,50 +2496,57 @@ void FixedwingPositionControl::navigateLoiter(const Vector2f &loiter_center, con // 90 deg clockwise rotation * loiter direction const Vector2f unit_path_tangent = loiter_direction_multiplier * Vector2f{-unit_vec_center_to_closest_pt(1), unit_vec_center_to_closest_pt(0)}; - float path_curvature = loiter_direction_multiplier / radius; - _target_bearing = atan2f(unit_path_tangent(1), unit_path_tangent(0)); + const float path_curvature = loiter_direction_multiplier / radius; _closest_point_on_path = unit_vec_center_to_closest_pt * radius + loiter_center; - _npfg.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, - loiter_center + unit_vec_center_to_closest_pt * radius, path_curvature); + return _directional_guidance.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, + loiter_center + unit_vec_center_to_closest_pt * radius, path_curvature); } -void FixedwingPositionControl::navigatePathTangent(const matrix::Vector2f &vehicle_pos, +DirectionalGuidanceOutput FixedwingPositionControl::navigatePathTangent(const matrix::Vector2f &vehicle_pos, const matrix::Vector2f &position_setpoint, const matrix::Vector2f &tangent_setpoint, const matrix::Vector2f &ground_vel, const matrix::Vector2f &wind_vel, const float &curvature) { if (tangent_setpoint.norm() <= FLT_EPSILON) { // degenerate case: no direction. maintain the last npfg command. - return; + return DirectionalGuidanceOutput{}; } const Vector2f unit_path_tangent{tangent_setpoint.normalized()}; - _target_bearing = atan2f(unit_path_tangent(1), unit_path_tangent(0)); _closest_point_on_path = position_setpoint; - _npfg.guideToPath(vehicle_pos, ground_vel, wind_vel, tangent_setpoint.normalized(), position_setpoint, curvature); + return _directional_guidance.guideToPath(vehicle_pos, ground_vel, wind_vel, tangent_setpoint.normalized(), + position_setpoint, + curvature); } -void FixedwingPositionControl::navigateBearing(const matrix::Vector2f &vehicle_pos, float bearing, +DirectionalGuidanceOutput FixedwingPositionControl::navigateBearing(const matrix::Vector2f &vehicle_pos, float bearing, const Vector2f &ground_vel, const Vector2f &wind_vel) { - const Vector2f unit_path_tangent = Vector2f{cosf(bearing), sinf(bearing)}; - _target_bearing = atan2f(unit_path_tangent(1), unit_path_tangent(0)); _closest_point_on_path = vehicle_pos; - _npfg.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, vehicle_pos, 0.0f); + return _directional_guidance.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, vehicle_pos, 0.0f); +} + +void FixedwingPositionControl::publish_lateral_guidance_status(const hrt_abstime now) +{ + fixed_wing_lateral_guidance_status_s fixed_wing_lateral_guidance_status{}; + + fixed_wing_lateral_guidance_status.timestamp = now; + fixed_wing_lateral_guidance_status.course_setpoint = _directional_guidance.getCourseSetpoint(); + fixed_wing_lateral_guidance_status.lateral_acceleration_ff = _directional_guidance.getLateralAccelerationSetpoint(); + fixed_wing_lateral_guidance_status.bearing_feas = _directional_guidance.getBearingFeasibility(); + fixed_wing_lateral_guidance_status.bearing_feas_on_track = _directional_guidance.getBearingFeasibilityOnTrack(); + fixed_wing_lateral_guidance_status.signed_track_error = _directional_guidance.getSignedTrackError(); + fixed_wing_lateral_guidance_status.track_error_bound = _directional_guidance.getTrackErrorBound(); + fixed_wing_lateral_guidance_status.adapted_period = _directional_guidance.getAdaptedPeriod(); + fixed_wing_lateral_guidance_status.wind_est_valid = _wind_valid; + + _fixed_wing_lateral_guidance_status_pub.publish(fixed_wing_lateral_guidance_status); } int FixedwingPositionControl::task_spawn(int argc, char *argv[]) { - bool vtol = false; - - if (argc > 1) { - if (strcmp(argv[1], "vtol") == 0) { - vtol = true; - } - } - - FixedwingPositionControl *instance = new FixedwingPositionControl(vtol); + FixedwingPositionControl *instance = new FixedwingPositionControl(); if (instance) { _object.store(instance); @@ -3370,12 +2587,11 @@ fw_pos_control is the fixed-wing position controller. PRINT_MODULE_USAGE_NAME("fw_pos_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_ARG("vtol", "VTOL mode", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; } -float FixedwingPositionControl::getLoadFactor() +float FixedwingPositionControl::getLoadFactor() const { float load_factor_from_bank_angle = 1.0f; @@ -3389,7 +2605,6 @@ float FixedwingPositionControl::getLoadFactor() } - extern "C" __EXPORT int fw_pos_control_main(int argc, char *argv[]) { return FixedwingPositionControl::main(argc, argv); diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index e56263c5e3..e7526dca40 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013-2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2013-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -35,13 +35,6 @@ /** * @file FixedwingPositionControl.hpp * Implementation of various fixed-wing position level navigation/control modes. - * - * The implementation for the controllers is in a separate library. This class only - * interfaces to the library. - * - * @author Lorenz Meier - * @author Thomas Gubler - * @author Andreas Antener */ #ifndef FIXEDWINGPOSITIONCONTROL_HPP_ @@ -49,15 +42,13 @@ #include "launchdetection/LaunchDetector.h" #include "runway_takeoff/RunwayTakeoff.h" -#include +#include "ControllerConfigurationHandler.hpp" #include - #include #include #include -#include -#include +#include #include #include #include @@ -67,24 +58,25 @@ #include #include #include +#include + #include #include #include #include #include -#include +#include +#include +#include #include #include #include #include -#include #include #include #include #include -#include #include -#include #include #include #include @@ -97,12 +89,10 @@ #include #include #include -#include #ifdef CONFIG_FIGURE_OF_EIGHT #include "figure_eight/FigureEight.hpp" #include - #endif // CONFIG_FIGURE_OF_EIGHT using namespace launchdetection; @@ -115,12 +105,6 @@ using matrix::Vector2f; // [m] initial distance of waypoint in front of plane in heading hold mode static constexpr float HDG_HOLD_DIST_NEXT = 3000.0f; -// [m] distance (plane to waypoint in front) at which waypoints are reset in heading hold mode -static constexpr float HDG_HOLD_REACHED_DIST = 1000.0f; - -// [m] distance by which previous waypoint is set behind the plane -static constexpr float HDG_HOLD_SET_BACK_DIST = 100.0f; - // [rad/s] max yawrate at which plane locks yaw for heading hold mode static constexpr float HDG_HOLD_YAWRATE_THRESH = 0.15f; @@ -138,9 +122,6 @@ static constexpr hrt_abstime TERRAIN_ALT_FIRST_MEASUREMENT_TIMEOUT = 10_s; // [.] max throttle from user which will not lead to motors spinning up in altitude controlled modes static constexpr float THROTTLE_THRESH = -.9f; -// [m/s/s] slew rate limit for airspeed setpoint changes -static constexpr float ASPD_SP_SLEW_RATE = 1.f; - // [us] time after which the wind estimate is disabled if no longer updating static constexpr hrt_abstime WIND_EST_TIMEOUT = 10_s; @@ -166,23 +147,14 @@ static constexpr float MANUAL_TOUCHDOWN_NUDGE_INPUT_DEADZONE = 0.15f; // [s] time interval after touchdown for ramping in runway clamping constraints (touchdown is assumed at FW_LND_TD_TIME after start of flare) static constexpr float POST_TOUCHDOWN_CLAMP_TIME = 0.5f; -// [m/s] maximum reference altitude rate threshhold -static constexpr float MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT = 0.1f; - -// [s] Timeout that has to pass in roll-constraining failsafe before warning is triggered -static constexpr uint64_t ROLL_WARNING_TIMEOUT = 2_s; - -// [-] Can-run threshold needed to trigger the roll-constraining failsafe warning -static constexpr float ROLL_WARNING_CAN_RUN_THRESHOLD = 0.9f; - -// [s] slew rate with which we change altitude time constant -static constexpr float TECS_ALT_TIME_CONST_SLEW_RATE = 1.0f; +// [] Stick deadzon +static constexpr float kStickDeadBand = 0.06f; class FixedwingPositionControl final : public ModuleBase, public ModuleParams, public px4::WorkItem { public: - FixedwingPositionControl(bool vtol = false); + FixedwingPositionControl(); ~FixedwingPositionControl() override; /** @see ModuleBase */ @@ -210,33 +182,31 @@ private: uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _pos_sp_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; - uORB::Publication _attitude_sp_pub; uORB::Publication _local_pos_sp_pub{ORB_ID(vehicle_local_position_setpoint)}; - uORB::Publication _npfg_status_pub{ORB_ID(npfg_status)}; - uORB::Publication _pos_ctrl_status_pub{ORB_ID(position_controller_status)}; uORB::Publication _pos_ctrl_landing_status_pub{ORB_ID(position_controller_landing_status)}; - uORB::Publication _tecs_status_pub{ORB_ID(tecs_status)}; uORB::Publication _launch_detection_status_pub{ORB_ID(launch_detection_status)}; uORB::PublicationMulti _orbit_status_pub{ORB_ID(orbit_status)}; uORB::Publication _landing_gear_pub {ORB_ID(landing_gear)}; uORB::Publication _flaps_setpoint_pub{ORB_ID(flaps_setpoint)}; uORB::Publication _spoilers_setpoint_pub{ORB_ID(spoilers_setpoint)}; - uORB::PublicationData _flight_phase_estimation_pub{ORB_ID(flight_phase_estimation)}; + uORB::PublicationData _lateral_ctrl_sp_pub{ORB_ID(fixed_wing_lateral_setpoint)}; + uORB::PublicationData _longitudinal_ctrl_sp_pub{ORB_ID(fixed_wing_longitudinal_setpoint)}; + uORB::Publication _fixed_wing_lateral_guidance_status_pub{ORB_ID(fixed_wing_lateral_guidance_status)}; manual_control_setpoint_s _manual_control_setpoint{}; position_setpoint_triplet_s _pos_sp_triplet{}; - vehicle_attitude_setpoint_s _att_sp{}; vehicle_control_mode_s _control_mode{}; vehicle_local_position_s _local_pos{}; vehicle_status_s _vehicle_status{}; + CombinedControllerConfigurationHandler _ctrl_configuration_handler; + Vector2f _lpos_where_backtrans_started; bool _position_setpoint_previous_valid{false}; @@ -272,12 +242,12 @@ private: // VEHICLE STATES + uint8_t _nav_state; + double _current_latitude{0}; double _current_longitude{0}; float _current_altitude{0.f}; - float _roll{0.f}; - float _pitch{0.0f}; float _yaw{0.0f}; float _yawrate{0.0f}; @@ -323,8 +293,8 @@ private: // true if a launch, specifically using the launch detector, has been detected bool _launch_detected{false}; - // [deg] global position of the vehicle at the time launch is detected (using launch detector) - Vector2d _launch_global_position{0, 0}; + // [deg] global position of the vehicle at the time launch is detected (using launch detector) or takeoff is started (runway) + Vector2d _takeoff_init_position{0, 0}; // [rad] current vehicle yaw at the time the launch is detected float _launch_current_yaw{0.f}; @@ -363,7 +333,6 @@ private: bool flaring{false}; hrt_abstime start_time{0}; // [us] float initial_height_rate_setpoint{0.0f}; // [m/s] - float initial_throttle_setpoint{0.0f}; } _flare_states; // [m] last terrain estimate which was valid @@ -381,9 +350,7 @@ private: // AIRSPEED float _airspeed_eas{0.f}; - float _eas2tas{1.f}; bool _airspeed_valid{false}; - float _air_density{atmosphere::kAirDensitySeaLevelStandardAtmos}; // [us] last time airspeed was received. used to detect timeouts. hrt_abstime _time_airspeed_last_valid{0}; @@ -397,24 +364,12 @@ private: hrt_abstime _time_wind_last_received{0}; // [us] - // TECS - - // total energy control system - airspeed / altitude control - TECS _tecs; - - bool _tecs_is_running{false}; - - // Smooths changes in the altitude tracking error time constant value - SlewRate _tecs_alt_time_const_slew_rate; - // VTOL / TRANSITION - bool _is_vtol_tailsitter{false}; matrix::Vector2d _transition_waypoint{(double)NAN, (double)NAN}; float _backtrans_heading{NAN}; // used to lock the initial heading for backtransition with no position control // ESTIMATOR RESET COUNTERS uint8_t _xy_reset_counter{0}; - uint8_t _z_reset_counter{0}; uint64_t _time_last_xy_reset{0}; // LATERAL-DIRECTIONAL GUIDANCE @@ -423,12 +378,7 @@ private: matrix::Vector2f _closest_point_on_path; // nonlinear path following guidance - lateral-directional position control - NPFG _npfg; - bool _need_report_npfg_uncertain_condition{false}; ///< boolean if reporting of uncertain npfg output condition is needed - hrt_abstime _time_since_first_reduced_roll{0U}; ///< absolute time since start when entering reduced roll angle for the first time - hrt_abstime _time_since_last_npfg_call{0U}; ///< absolute time since start when the npfg reduced roll angle calculations was last performed - - PerformanceModel _performance_model; + DirectionalGuidance _directional_guidance; // LANDING GEAR int8_t _new_landing_gear_position{landing_gear_s::GEAR_KEEP}; @@ -439,7 +389,6 @@ private: hrt_abstime _time_in_fixed_bank_loiter{0}; // [us] float _min_current_sp_distance_xy{FLT_MAX}; - float _target_bearing{0.0f}; // [rad] #ifdef CONFIG_FIGURE_OF_EIGHT /* Loitering */ @@ -451,11 +400,10 @@ private: * @param control_interval Time since last position control call [s] * @param curr_pos the current 2D absolute position of the vehicle in [deg]. * @param ground_speed the 2D ground speed of the vehicle in [m/s]. - * @param pos_sp_prev the previous position setpoint. * @param pos_sp_curr the current position setpoint. */ void controlAutoFigureEight(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, - const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr); + const position_setpoint_s &pos_sp_curr); void publishFigureEightStatus(const position_setpoint_s pos_sp); #endif // CONFIG_FIGURE_OF_EIGHT @@ -465,27 +413,18 @@ private: // Update subscriptions void airspeed_poll(); - void control_update(); + void manual_control_setpoint_poll(); void vehicle_attitude_poll(); void vehicle_command_poll(); void vehicle_control_mode_poll(); - void vehicle_status_poll(); - void wind_poll(); - void status_publish(); + void wind_poll(const hrt_abstime now); + void landing_status_publish(); - void tecs_status_publish(float alt_sp, float equivalent_airspeed_sp, float true_airspeed_derivative_raw, - float throttle_trim); - void publishLocalPositionSetpoint(const position_setpoint_s ¤t_waypoint); - float getLoadFactor(); - /** - * @brief Get the NPFG roll setpoint with mitigation strategy if npfg is not certain about its output - * - * @return roll setpoint - */ - float getCorrectedNpfgRollSetpoint(); + void publishLocalPositionSetpoint(const position_setpoint_s ¤t_waypoint); + float getLoadFactor() const; /** * @brief Sets the landing abort status and publishes landing status. @@ -503,24 +442,6 @@ private: */ bool checkLandingAbortBitMask(const uint8_t automatic_abort_criteria_bitmask, uint8_t landing_abort_criterion); - /** - * @brief Get a new waypoint based on heading and distance from current position - * - * @param heading the heading to fly to - * @param distance the distance of the generated waypoint - * @param waypoint_prev the waypoint at the current position - * @param waypoint_next the waypoint in the heading direction - */ - void get_waypoint_heading_distance(float heading, position_setpoint_s &waypoint_prev, - position_setpoint_s &waypoint_next, bool flag_init); - - /** - * @brief Return the terrain estimate during takeoff or takeoff_alt if terrain estimate is not available - * - * @param takeoff_alt Altitude AMSL at launch or when runway takeoff is detected [m] - */ - float get_terrain_altitude_takeoff(float takeoff_alt); - /** * @brief Maps the manual control setpoint (pilot sticks) to height rate commands * @@ -535,13 +456,6 @@ private: */ void updateManualTakeoffStatus(); - /** - * @brief Update desired altitude base on user pitch stick input - * - * @param dt Time step - */ - void update_desired_altitude(float dt); - /** * @brief Updates timing information for landed and in-air states. * @@ -585,19 +499,15 @@ private: * @brief Controls altitude and airspeed for a fixed-bank loiter. * * Used as a failsafe mode after a lateral position estimate failure. - * - * @param control_interval Time since last position control call [s] */ - void control_auto_fixed_bank_alt_hold(const float control_interval); + void control_auto_fixed_bank_alt_hold(); /** * @brief Control airspeed with a fixed descent rate and roll angle. * * Used as a failsafe mode after a lateral position estimate failure. - * - * @param control_interval Time since last position control call [s] */ - void control_auto_descend(const float control_interval); + void control_auto_descend(); /** * @brief Vehicle control for position waypoints. @@ -617,12 +527,11 @@ private: * @param control_interval Time since last position control call [s] * @param curr_pos Current 2D local position vector of vehicle [m] * @param ground_speed Local 2D ground speed of vehicle [m/s] - * @param pos_sp_prev previous position setpoint * @param pos_sp_curr current position setpoint * @param pos_sp_next next position setpoint */ void control_auto_loiter(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, - const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr, const position_setpoint_s &pos_sp_next); + const position_setpoint_s &pos_sp_curr, const position_setpoint_s &pos_sp_next); /** @@ -703,11 +612,13 @@ private: /** * @brief Controls user commanded altitude, airspeed, and bearing. * + * @param now Current system time [us] * @param control_interval Time since last position control call [s] * @param curr_pos Current 2D local position vector of vehicle [m] * @param ground_speed Local 2D ground speed of vehicle [m/s] */ - void control_manual_position(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed); + void control_manual_position(const hrt_abstime now, const float control_interval, const Vector2d &curr_pos, + const Vector2f &ground_speed); /** * @brief Holds the initial heading during the course of a transition to hover. Used when there is no local @@ -724,26 +635,8 @@ private: void control_backtransition_line_follow(const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr); - float get_tecs_pitch(); - float get_tecs_thrust(); - float get_manual_airspeed_setpoint(); - /** - * @brief Returns an adapted calibrated airspeed setpoint - * - * Adjusts the setpoint for wind, accelerated stall, and slew rates. - * - * @param control_interval Time since the last position control update [s] - * @param calibrated_airspeed_setpoint Calibrated airspeed septoint (generally from the position setpoint) [m/s] - * @param calibrated_min_airspeed Minimum calibrated airspeed [m/s] - * @param ground_speed Vehicle ground velocity vector (NE) [m/s] - * @param in_takeoff_situation Vehicle is currently in a takeoff situation - * @return Adjusted calibrated airspeed setpoint [m/s] - */ - float adapt_airspeed_setpoint(const float control_interval, float calibrated_airspeed_setpoint, - float calibrated_min_airspeed, const Vector2f &ground_speed, bool in_takeoff_situation = false); - void reset_takeoff_state(); void reset_landing_state(); @@ -758,39 +651,7 @@ private: void publishOrbitStatus(const position_setpoint_s pos_sp); - SlewRate _airspeed_slew_rate_controller; - SlewRate _roll_slew_rate; - - /** - * @brief A wrapper function to call the TECS implementation - * - * @param control_interval Time since the last position control update [s] - * @param alt_sp Altitude setpoint, AMSL [m] - * @param airspeed_sp Calibrated airspeed setpoint [m/s] - * @param pitch_min_rad Nominal pitch angle command minimum [rad] - * @param pitch_max_rad Nominal pitch angle command maximum [rad] - * @param throttle_min Minimum throttle command [0,1] - * @param throttle_max Maximum throttle command [0,1] - * @param desired_max_sink_rate The desired max sink rate commandable when altitude errors are large [m/s] - * @param desired_max_climb_rate The desired max climb rate commandable when altitude errors are large [m/s] - * @param is_low_height Define whether we are in low-height flight for tighter altitude tracking - * @param disable_underspeed_detection True if underspeed detection should be disabled - * @param hgt_rate_sp Height rate setpoint [m/s] - */ - void tecs_update_pitch_throttle(const float control_interval, float alt_sp, float airspeed_sp, float pitch_min_rad, - float pitch_max_rad, float throttle_min, float throttle_max, - const float desired_max_sink_rate, const float desired_max_climb_rate, const bool is_low_height, - bool disable_underspeed_detection = false, float hgt_rate_sp = NAN); - - /** - * @brief Constrains the roll angle setpoint near ground to avoid wingtip strike. - * - * @param roll_setpoint Unconstrained roll angle setpoint [rad] - * @param altitude Vehicle altitude (AMSL) [m] - * @param terrain_altitude Terrain altitude (AMSL) [m] - * @return Constrained roll angle setpoint [rad] - */ - float constrainRollNearGround(const float roll_setpoint, const float altitude, const float terrain_altitude) const; + float getMaxRollAngleNearGround(const float altitude, const float terrain_altitude) const; /** * @brief Calculates the touchdown position for landing with optional manual lateral adjustments. @@ -838,21 +699,6 @@ private: void initializeAutoLanding(const hrt_abstime &now, const position_setpoint_s &pos_sp_prev, const float land_point_alt, const Vector2f &local_position, const Vector2f &local_land_point); - /* - * Checks if the vehicle satisfies conditions for low-height flight - * - * @return bool True if conditions are satisfied, false otherwise - */ - bool checkLowHeightConditions(); - - /* - * Updates TECS altitude time constant according to the is_low_height parameter. - * - * @param is_low_height Boolean flag defining whether we are in low-height flight - * @param dt Update time step [s] - */ - void updateTECSAltitudeTimeConstant(const bool is_low_height, const float dt); - /* * Waypoint handling logic following closely to the ECL_L1_Pos_Controller * method of the same name. Takes two waypoints, steering the vehicle to track @@ -864,9 +710,10 @@ private: * @param[in] ground_vel Vehicle ground velocity vector [m/s] * @param[in] wind_vel Wind velocity vector [m/s] */ - void navigateWaypoints(const matrix::Vector2f &start_waypoint, const matrix::Vector2f &end_waypoint, - const matrix::Vector2f &vehicle_pos, const matrix::Vector2f &ground_vel, - const matrix::Vector2f &wind_vel); + DirectionalGuidanceOutput navigateWaypoints(const matrix::Vector2f &start_waypoint, + const matrix::Vector2f &end_waypoint, + const matrix::Vector2f &vehicle_pos, const matrix::Vector2f &ground_vel, + const matrix::Vector2f &wind_vel); /* * Takes one waypoint and steers the vehicle towards this. @@ -879,8 +726,8 @@ private: * @param[in] ground_vel Vehicle ground velocity vector [m/s] * @param[in] wind_vel Wind velocity vector [m/s] */ - void navigateWaypoint(const matrix::Vector2f &waypoint_pos, const matrix::Vector2f &vehicle_pos, - const matrix::Vector2f &ground_vel, const matrix::Vector2f &wind_vel); + DirectionalGuidanceOutput navigateWaypoint(const matrix::Vector2f &waypoint_pos, const matrix::Vector2f &vehicle_pos, + const matrix::Vector2f &ground_vel, const matrix::Vector2f &wind_vel); /* * Line (infinite) following logic. Two points on the line are used to define the @@ -893,8 +740,9 @@ private: * @param[in] ground_vel Vehicle ground velocity vector [m/s] * @param[in] wind_vel Wind velocity vector [m/s] */ - void navigateLine(const Vector2f &point_on_line_1, const Vector2f &point_on_line_2, const Vector2f &vehicle_pos, - const Vector2f &ground_vel, const Vector2f &wind_vel); + DirectionalGuidanceOutput navigateLine(const Vector2f &point_on_line_1, const Vector2f &point_on_line_2, + const Vector2f &vehicle_pos, + const Vector2f &ground_vel, const Vector2f &wind_vel); /* * Line (infinite) following logic. One point on the line and a line bearing are used to define @@ -907,8 +755,9 @@ private: * @param[in] ground_vel Vehicle ground velocity vector [m/s] * @param[in] wind_vel Wind velocity vector [m/s] */ - void navigateLine(const Vector2f &point_on_line, const float line_bearing, const Vector2f &vehicle_pos, - const Vector2f &ground_vel, const Vector2f &wind_vel); + DirectionalGuidanceOutput navigateLine(const Vector2f &point_on_line, const float line_bearing, + const Vector2f &vehicle_pos, + const Vector2f &ground_vel, const Vector2f &wind_vel); /* * Loitering (unlimited) logic. Takes loiter center, radius, and direction and @@ -922,9 +771,9 @@ private: * @param[in] ground_vel Vehicle ground velocity vector [m/s] * @param[in] wind_vel Wind velocity vector [m/s] */ - void navigateLoiter(const matrix::Vector2f &loiter_center, const matrix::Vector2f &vehicle_pos, - float radius, bool loiter_direction_counter_clockwise, const matrix::Vector2f &ground_vel, - const matrix::Vector2f &wind_vel); + DirectionalGuidanceOutput navigateLoiter(const matrix::Vector2f &loiter_center, const matrix::Vector2f &vehicle_pos, + float radius, bool loiter_direction_counter_clockwise, const matrix::Vector2f &ground_vel, + const matrix::Vector2f &wind_vel); /* * Path following logic. Takes poisiton, path tangent, curvature and @@ -939,9 +788,10 @@ private: * @param[in] wind_vel Wind velocity vector [m/s] * @param[in] curvature of the path setpoint [1/m] */ - void navigatePathTangent(const matrix::Vector2f &vehicle_pos, const matrix::Vector2f &position_setpoint, - const matrix::Vector2f &tangent_setpoint, - const matrix::Vector2f &ground_vel, const matrix::Vector2f &wind_vel, const float &curvature); + DirectionalGuidanceOutput navigatePathTangent(const matrix::Vector2f &vehicle_pos, + const matrix::Vector2f &position_setpoint, + const matrix::Vector2f &tangent_setpoint, + const matrix::Vector2f &ground_vel, const matrix::Vector2f &wind_vel, const float &curvature); /* * Navigate on a fixed bearing. @@ -954,23 +804,22 @@ private: * @param[in] ground_vel Vehicle ground velocity vector [m/s] * @param[in] wind_vel Wind velocity vector [m/s] */ - void navigateBearing(const matrix::Vector2f &vehicle_pos, float bearing, const matrix::Vector2f &ground_vel, - const matrix::Vector2f &wind_vel); + DirectionalGuidanceOutput navigateBearing(const matrix::Vector2f &vehicle_pos, float bearing, + const matrix::Vector2f &ground_vel, + const matrix::Vector2f &wind_vel); + + void control_idle(); + void publish_lateral_guidance_status(const hrt_abstime now); + + float rollAngleToLateralAccel(float roll_body) const; DEFINE_PARAMETERS( - (ParamFloat) _param_fw_gnd_spd_min, - - (ParamFloat) _param_fw_pn_r_slew_max, (ParamFloat) _param_fw_r_lim, (ParamFloat) _param_npfg_period, (ParamFloat) _param_npfg_damping, (ParamBool) _param_npfg_en_period_lb, (ParamBool) _param_npfg_en_period_ub, - (ParamBool) _param_npfg_en_track_keeping, - (ParamBool) _param_npfg_en_min_gsp, - (ParamBool) _param_npfg_en_wind_reg, - (ParamFloat) _param_npfg_track_keeping_gsp_max, (ParamFloat) _param_npfg_roll_time_const, (ParamFloat) _param_npfg_switch_distance_multiplier, (ParamFloat) _param_npfg_period_safety_factor, @@ -980,80 +829,46 @@ private: (ParamFloat) _param_fw_lnd_fl_pmax, (ParamFloat) _param_fw_lnd_fl_pmin, (ParamFloat) _param_fw_lnd_flalt, - (ParamFloat) _param_fw_thrtc_sc, - (ParamFloat) _param_fw_t_thr_low_hgt, (ParamBool) _param_fw_lnd_earlycfg, (ParamInt) _param_fw_lnd_useter, (ParamFloat) _param_fw_p_lim_max, (ParamFloat) _param_fw_p_lim_min, - - (ParamFloat) _param_fw_t_hrate_ff, - (ParamFloat) _param_fw_t_h_error_tc, - (ParamFloat) _param_fw_t_fast_alt_err, - (ParamFloat) _param_fw_t_thr_integ, - (ParamFloat) _param_fw_t_I_gain_pit, - (ParamFloat) _param_fw_t_ptch_damp, - (ParamFloat) _param_fw_t_rll2thr, - (ParamFloat) _param_fw_t_sink_max, - (ParamFloat) _param_fw_t_spdweight, - (ParamFloat) _param_fw_t_tas_error_tc, - (ParamFloat) _param_fw_t_thr_damping, - (ParamFloat) _param_fw_t_vert_acc, - (ParamFloat) _param_ste_rate_time_const, - (ParamFloat) _param_seb_rate_ff, (ParamFloat) _param_climbrate_target, (ParamFloat) _param_sinkrate_target, - (ParamFloat) _param_speed_standard_dev, - (ParamFloat) _param_speed_rate_standard_dev, - (ParamFloat) _param_process_noise_standard_dev, - (ParamFloat) _param_fw_thr_idle, (ParamFloat) _param_fw_thr_max, (ParamFloat) _param_fw_thr_min, - (ParamFloat) _param_fw_thr_slew_max, - (ParamFloat) _param_fw_flaps_lnd_scl, (ParamFloat) _param_fw_flaps_to_scl, (ParamFloat) _param_fw_spoilers_lnd, - (ParamInt) _param_fw_pos_stk_conf, - (ParamInt) _param_nav_gpsf_lt, (ParamFloat) _param_nav_gpsf_r, + (ParamFloat) _param_t_spdweight, // external parameters (ParamBool) _param_fw_use_airspd, - - (ParamFloat) _param_fw_psp_off, - (ParamFloat) _param_nav_loiter_rad, - (ParamFloat) _takeoff_pitch_min, - (ParamFloat) _param_nav_fw_alt_rad, - (ParamFloat) _param_fw_wing_span, (ParamFloat) _param_fw_wing_height, - - (ParamFloat) _param_rwto_npfg_period, (ParamBool) _param_rwto_nudge, - (ParamFloat) _param_fw_lnd_fl_time, (ParamFloat) _param_fw_lnd_fl_sink, (ParamFloat) _param_fw_lnd_td_time, (ParamFloat) _param_fw_lnd_td_off, (ParamInt) _param_fw_lnd_nudge, (ParamInt) _param_fw_lnd_abort, - - (ParamFloat) _param_fw_wind_arsp_sc, - (ParamFloat) _param_fw_tko_airspd, - (ParamFloat) _param_rwto_psp, - (ParamBool) _param_fw_laun_detcn_on + (ParamBool) _param_fw_laun_detcn_on, + (ParamFloat) _param_fw_airspd_max, + (ParamFloat) _param_fw_airspd_min, + (ParamFloat) _param_fw_airspd_trim, + (ParamFloat) _param_fw_t_clmb_max ) - }; #endif // FIXEDWINGPOSITIONCONTROL_HPP_ diff --git a/src/modules/fw_pos_control/figure_eight/FigureEight.cpp b/src/modules/fw_pos_control/figure_eight/FigureEight.cpp index d0ce50a033..9ab672d964 100644 --- a/src/modules/fw_pos_control/figure_eight/FigureEight.cpp +++ b/src/modules/fw_pos_control/figure_eight/FigureEight.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2022-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -48,11 +48,10 @@ static constexpr bool SOUTH_CIRCLE_IS_COUNTER_CLOCKWISE{true}; static constexpr float DEFAULT_MAJOR_TO_MINOR_AXIS_RATIO{2.5f}; static constexpr float MINIMAL_FEASIBLE_MAJOR_TO_MINOR_AXIS_RATIO{2.0f}; -FigureEight::FigureEight(NPFG &npfg, matrix::Vector2f &wind_vel, float &eas2tas) : +FigureEight::FigureEight(DirectionalGuidance &npfg, matrix::Vector2f &wind_vel) : ModuleParams(nullptr), - _npfg(npfg), - _wind_vel(wind_vel), - _eas2tas(eas2tas) + _directional_guidance(npfg), + _wind_vel(wind_vel) { } @@ -64,8 +63,9 @@ void FigureEight::resetPattern() _pos_passed_circle_center_along_major_axis = false; } -void FigureEight::updateSetpoint(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, float target_airspeed) +DirectionalGuidanceOutput FigureEight::updateSetpoint(const matrix::Vector2f &curr_pos_local, + const matrix::Vector2f &ground_speed, + const FigureEightPatternParameters ¶meters) { // Sanitize inputs FigureEightPatternParameters valid_parameters{sanitizeParameters(parameters)}; @@ -81,7 +81,7 @@ void FigureEight::updateSetpoint(const matrix::Vector2f &curr_pos_local, const m updateSegment(curr_pos_local, valid_parameters, pattern_points); // Apply control logic based on segment - applyControl(curr_pos_local, ground_speed, valid_parameters, target_airspeed, pattern_points); + return applyControl(curr_pos_local, ground_speed, valid_parameters, pattern_points); } FigureEight::FigureEightPatternParameters FigureEight::sanitizeParameters(const FigureEightPatternParameters @@ -118,7 +118,8 @@ void FigureEight::initializePattern(const matrix::Vector2f &curr_pos_local, cons const bool north_is_closer = north_center_to_pos_local.norm() < south_center_to_pos_local.norm(); // Get the normalized switch distance. - float switch_distance_normalized = _npfg.switchDistance(FLT_MAX) * NORMALIZED_MAJOR_RADIUS / parameters.loiter_radius; + float switch_distance_normalized = _directional_guidance.switchDistance(FLT_MAX) * NORMALIZED_MAJOR_RADIUS / + parameters.loiter_radius; //Far away from current figure of eight. Fly towards closer circle @@ -194,7 +195,8 @@ void FigureEight::updateSegment(const matrix::Vector2f &curr_pos_local, const Fi calculatePositionToCenterNormalizedRotated(center_to_pos_local, curr_pos_local, parameters); // Get the normalized switch distance. - float switch_distance_normalized = _npfg.switchDistance(FLT_MAX) * NORMALIZED_MAJOR_RADIUS / parameters.loiter_radius; + float switch_distance_normalized = _directional_guidance.switchDistance(FLT_MAX) * NORMALIZED_MAJOR_RADIUS / + parameters.loiter_radius; // Update segment if segment exit condition has been reached switch (_current_segment) { @@ -275,56 +277,60 @@ void FigureEight::updateSegment(const matrix::Vector2f &curr_pos_local, const Fi } } -void FigureEight::applyControl(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, float target_airspeed, - const FigureEightPatternPoints &pattern_points) +DirectionalGuidanceOutput FigureEight::applyControl(const matrix::Vector2f &curr_pos_local, + const matrix::Vector2f &ground_speed, + const FigureEightPatternParameters ¶meters, + const FigureEightPatternPoints &pattern_points) { Vector2f center_to_pos_local; calculatePositionToCenterNormalizedRotated(center_to_pos_local, curr_pos_local, parameters); switch (_current_segment) { case FigureEightSegment::SEGMENT_CIRCLE_NORTH: { - applyCircle(NORTH_CIRCLE_IS_COUNTER_CLOCKWISE, pattern_points.normalized_north_circle_offset, curr_pos_local, - ground_speed, parameters, target_airspeed); + return applyCircle(NORTH_CIRCLE_IS_COUNTER_CLOCKWISE, pattern_points.normalized_north_circle_offset, curr_pos_local, + ground_speed, parameters); } break; case FigureEightSegment::SEGMENT_NORTHEAST_SOUTHWEST: { // Follow path from north-east to south-west - applyLine(pattern_points.normalized_north_exit_offset, pattern_points.normalized_south_entry_offset, curr_pos_local, - ground_speed, parameters, target_airspeed); + return applyLine(pattern_points.normalized_north_exit_offset, pattern_points.normalized_south_entry_offset, + curr_pos_local, + ground_speed, parameters); } break; case FigureEightSegment::SEGMENT_CIRCLE_SOUTH: { - applyCircle(SOUTH_CIRCLE_IS_COUNTER_CLOCKWISE, pattern_points.normalized_south_circle_offset, curr_pos_local, - ground_speed, parameters, target_airspeed); + return applyCircle(SOUTH_CIRCLE_IS_COUNTER_CLOCKWISE, pattern_points.normalized_south_circle_offset, curr_pos_local, + ground_speed, parameters); } break; case FigureEightSegment::SEGMENT_SOUTHEAST_NORTHWEST: { // follow path from south-east to north-west - applyLine(pattern_points.normalized_south_exit_offset, pattern_points.normalized_north_entry_offset, curr_pos_local, - ground_speed, parameters, target_airspeed); + return applyLine(pattern_points.normalized_south_exit_offset, pattern_points.normalized_north_entry_offset, + curr_pos_local, + ground_speed, parameters); } break; case FigureEightSegment::SEGMENT_POINT_SOUTHWEST: { // Follow path from current position to south-west - applyLine(center_to_pos_local, pattern_points.normalized_south_entry_offset, curr_pos_local, - ground_speed, parameters, target_airspeed); + return applyLine(center_to_pos_local, pattern_points.normalized_south_entry_offset, curr_pos_local, + ground_speed, parameters); } break; case FigureEightSegment::SEGMENT_POINT_NORTHWEST: { // Follow path from current position to north-west - applyLine(center_to_pos_local, pattern_points.normalized_north_entry_offset, curr_pos_local, - ground_speed, parameters, target_airspeed); + return applyLine(center_to_pos_local, pattern_points.normalized_north_entry_offset, curr_pos_local, + ground_speed, parameters); } break; case FigureEightSegment::SEGMENT_UNDEFINED: default: + return DirectionalGuidanceOutput{}; break; } } @@ -356,9 +362,10 @@ float FigureEight::calculateRotationAngle(const FigureEightPatternParameters &pa return yaw_rotation; } -void FigureEight::applyCircle(bool loiter_direction_counter_clockwise, const matrix::Vector2f &normalized_circle_offset, - const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, float target_airspeed) +DirectionalGuidanceOutput FigureEight::applyCircle(bool loiter_direction_counter_clockwise, + const matrix::Vector2f &normalized_circle_offset, + const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, + const FigureEightPatternParameters ¶meters) { const float loiter_direction_multiplier = loiter_direction_counter_clockwise ? -1.f : 1.f; @@ -366,8 +373,6 @@ void FigureEight::applyCircle(bool loiter_direction_counter_clockwise, const mat Vector2f circle_offset_rotated = Dcm2f(calculateRotationAngle(parameters)) * circle_offset; Vector2f circle_center = parameters.center_pos_local + circle_offset_rotated; - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_param_fw_airspd_max.get() * _eas2tas); const Vector2f vector_center_to_vehicle = curr_pos_local - circle_center; const float dist_to_center = vector_center_to_vehicle.norm(); @@ -392,16 +397,14 @@ void FigureEight::applyCircle(bool loiter_direction_counter_clockwise, const mat float path_curvature = loiter_direction_multiplier / parameters.loiter_minor_radius; _target_bearing = atan2f(unit_path_tangent(1), unit_path_tangent(0)); _closest_point_on_path = unit_vec_center_to_closest_pt * parameters.loiter_minor_radius + circle_center; - _npfg.guideToPath(curr_pos_local, ground_speed, _wind_vel, unit_path_tangent, - _closest_point_on_path, path_curvature); + return _directional_guidance.guideToPath(curr_pos_local, ground_speed, _wind_vel, unit_path_tangent, + _closest_point_on_path, path_curvature); - _roll_setpoint = _npfg.getRollSetpoint(); - _indicated_airspeed_setpoint = _npfg.getAirspeedRef() / _eas2tas; } -void FigureEight::applyLine(const matrix::Vector2f &normalized_line_start_offset, - const matrix::Vector2f &normalized_line_end_offset, const matrix::Vector2f &curr_pos_local, - const matrix::Vector2f &ground_speed, const FigureEightPatternParameters ¶meters, float target_airspeed) +DirectionalGuidanceOutput FigureEight::applyLine(const matrix::Vector2f &normalized_line_start_offset, + const matrix::Vector2f &normalized_line_end_offset, const matrix::Vector2f &curr_pos_local, + const matrix::Vector2f &ground_speed, const FigureEightPatternParameters ¶meters) { const Dcm2f rotation_matrix(calculateRotationAngle(parameters)); @@ -414,15 +417,12 @@ void FigureEight::applyLine(const matrix::Vector2f &normalized_line_start_offset const Vector2f end_offset_rotated = rotation_matrix * end_offset; const Vector2f line_segment_end_position = parameters.center_pos_local + end_offset_rotated; - _npfg.setAirspeedNom(target_airspeed * _eas2tas); - _npfg.setAirspeedMax(_param_fw_airspd_max.get() * _eas2tas); const Vector2f path_tangent = line_segment_end_position - line_segment_start_position; const Vector2f unit_path_tangent = path_tangent.normalized(); _target_bearing = atan2f(unit_path_tangent(1), unit_path_tangent(0)); const Vector2f vector_A_to_vehicle = curr_pos_local - line_segment_start_position; _closest_point_on_path = line_segment_start_position + vector_A_to_vehicle.dot(unit_path_tangent) * unit_path_tangent; - _npfg.guideToPath(curr_pos_local, ground_speed, _wind_vel, path_tangent.normalized(), line_segment_start_position, - 0.0f); - _roll_setpoint = _npfg.getRollSetpoint(); - _indicated_airspeed_setpoint = _npfg.getAirspeedRef() / _eas2tas; + return _directional_guidance.guideToPath(curr_pos_local, ground_speed, _wind_vel, path_tangent.normalized(), + line_segment_start_position, + 0.0f); } diff --git a/src/modules/fw_pos_control/figure_eight/FigureEight.hpp b/src/modules/fw_pos_control/figure_eight/FigureEight.hpp index b3c55c840b..297e07942c 100644 --- a/src/modules/fw_pos_control/figure_eight/FigureEight.hpp +++ b/src/modules/fw_pos_control/figure_eight/FigureEight.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -45,7 +45,7 @@ #include #include -#include "lib/npfg/npfg.hpp" +#include "lib/npfg/DirectionalGuidance.hpp" class FigureEight : public ModuleParams { @@ -87,9 +87,8 @@ public: * * @param[in] npfg is the reference to the parent npfg object. * @param[in] wind_vel is the reference to the parent wind velocity [m/s]. - * @param[in] eas2tas is the reference to the parent indicated airspeed to true airspeed conversion. */ - FigureEight(NPFG &npfg, matrix::Vector2f &wind_vel, float &eas2tas); + FigureEight(DirectionalGuidance &directional_guidance, matrix::Vector2f &wind_vel); /** * @brief reset the figure eight pattern. @@ -100,27 +99,14 @@ public: void resetPattern(); /** - * @brief Update roll and airspeed setpoint. + * @brief Update roll setpoint * * @param[in] curr_pos_local is the current local position of the vehicle in [m]. * @param[in] ground_speed is the current ground speed of the vehicle in [m/s]. * @param[in] parameters is the parameter set defining the figure eight shape. - * @param[in] target_airspeed is the current targeted indicated airspeed [m/s]. */ - void updateSetpoint(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, float target_airspeed); - /** - * @brief Get the roll setpoint - * - * @return the roll setpoint in [rad]. - */ - float getRollSetpoint() const {return _roll_setpoint;}; - /** - * @brief Get the indicated airspeed setpoint - * - * @return the indicated airspeed setpoint in [m/s]. - */ - float getAirspeedSetpoint() const {return _indicated_airspeed_setpoint;}; + DirectionalGuidanceOutput updateSetpoint(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, + const FigureEightPatternParameters ¶meters); /** * @brief Get the target bearing of current point on figure of eight * @@ -134,7 +120,6 @@ public: */ matrix::Vector2f getClosestPoint() const {return _closest_point_on_path;}; - private: /** * @brief @@ -172,12 +157,11 @@ private: * @param[in] curr_pos_local is the current local position of the vehicle in [m]. * @param[in] ground_speed is the current ground speed of the vehicle in [m/s]. * @param[in] parameters is the parameter set defining the figure eight shape. - * @param[in] target_airspeed is the current targeted indicated airspeed [m/s]. * @param[in] pattern_points are the relevant points defining the figure eight pattern. */ - void applyControl(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, float target_airspeed, - const FigureEightPatternPoints &pattern_points); + DirectionalGuidanceOutput applyControl(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, + const FigureEightPatternParameters ¶meters, + const FigureEightPatternPoints &pattern_points); /** * @brief Update active segment. * @@ -212,11 +196,11 @@ private: * @param[in] curr_pos_local is the current local position of the vehicle in [m]. * @param[in] ground_speed is the current ground speed of the vehicle in [m/s]. * @param[in] parameters is the parameter set defining the figure eight shape. - * @param[in] target_airspeed is the current targeted indicated airspeed [m/s]. */ - void applyCircle(bool loiter_direction_counter_clockwise, const matrix::Vector2f &normalized_circle_offset, - const matrix::Vector2f &curr_pos_local, - const matrix::Vector2f &ground_speed, const FigureEightPatternParameters ¶meters, float target_airspeed); + DirectionalGuidanceOutput applyCircle(bool loiter_direction_counter_clockwise, + const matrix::Vector2f &normalized_circle_offset, + const matrix::Vector2f &curr_pos_local, + const matrix::Vector2f &ground_speed, const FigureEightPatternParameters ¶meters); /** * @brief Apply path lateral control * @@ -225,18 +209,18 @@ private: * @param[in] curr_pos_local is the current local position of the vehicle in [m]. * @param[in] ground_speed is the current ground speed of the vehicle in [m/s]. * @param[in] parameters is the parameter set defining the figure eight shape. - * @param[in] target_airspeed is the current targeted indicated airspeed [m/s]. */ - void applyLine(const matrix::Vector2f &normalized_line_start_offset, const matrix::Vector2f &normalized_line_end_offset, - const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, float target_airspeed); + DirectionalGuidanceOutput applyLine(const matrix::Vector2f &normalized_line_start_offset, + const matrix::Vector2f &normalized_line_end_offset, + const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, + const FigureEightPatternParameters ¶meters); private: /** * @brief npfg lateral control object. * */ - NPFG &_npfg; + DirectionalGuidance &_directional_guidance; /** * @brief Wind velocity in [m/s]. @@ -244,24 +228,9 @@ private: */ const matrix::Vector2f &_wind_vel; /** - * @brief Conversion factor from indicated to true airspeed. - * - */ - const float &_eas2tas; - /** - * @brief Roll setpoint in [rad]. - * - */ - float _roll_setpoint; - /** - * @brief Indicated airspeed setpoint in [m/s]. - * - */ - float _indicated_airspeed_setpoint; - /** - * @brief active figure eight position setpoint. - * - */ + * @brief active figure eight position setpoint. + * + */ FigureEightPatternParameters _active_parameters; /** diff --git a/src/modules/fw_pos_control/fw_path_navigation_params.c b/src/modules/fw_pos_control/fw_path_navigation_params.c index 2e2005997a..9f82c22fb4 100644 --- a/src/modules/fw_pos_control/fw_path_navigation_params.c +++ b/src/modules/fw_pos_control/fw_path_navigation_params.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2013-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -31,20 +31,6 @@ * ****************************************************************************/ -/** - * Path navigation roll slew rate limit. - * - * Maximum change in roll angle setpoint per second. - * Applied in all Auto modes, plus manual Position & Altitude modes. - * - * @unit deg/s - * @min 0 - * @decimal 0 - * @increment 1 - * @group FW Path Control - */ -PARAM_DEFINE_FLOAT(FW_PN_R_SLEW_MAX, 90.0f); - /** * NPFG period * @@ -93,48 +79,6 @@ PARAM_DEFINE_INT32(NPFG_LB_PERIOD, 1); */ PARAM_DEFINE_INT32(NPFG_UB_PERIOD, 1); -/** - * Enable track keeping excess wind handling logic. - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_TRACK_KEEP, 1); - -/** - * Enable minimum forward ground speed maintaining excess wind handling logic - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_EN_MIN_GSP, 1); - -/** - * Enable wind excess regulation. - * - * Disabling this parameter further disables all other airspeed incrementation options. - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_WIND_REG, 1); - -/** - * Maximum, minimum forward ground speed for track keeping in excess wind - * - * The maximum value of the minimum forward ground speed that may be commanded - * by the track keeping excess wind handling logic. Commanded in full at the normalized - * track error fraction of the track error boundary and reduced to zero on track. - * - * @unit m/s - * @min 0.0 - * @max 10.0 - * @decimal 1 - * @increment 0.5 - * @group FW NPFG Control - */ -PARAM_DEFINE_FLOAT(NPFG_GSP_MAX_TK, 5.0f); - /** * Roll time constant * @@ -178,20 +122,6 @@ PARAM_DEFINE_FLOAT(NPFG_SW_DST_MLT, 0.32f); */ PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f); - -/** - * Throttle max slew rate - * - * Maximum slew rate for the commanded throttle - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); - /** * Minimum pitch angle setpoint * @@ -423,157 +353,6 @@ PARAM_DEFINE_FLOAT(FW_LND_AIRSPD, -1.f); */ PARAM_DEFINE_FLOAT(FW_LND_THRTC_SC, 1.0f); -/** - * Low-height threshold for tighter altitude tracking - * - * Height above ground threshold below which tighter altitude - * tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly - * (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC - * to FW_LND_THRTC_SC*FW_T_ALT_TC. - * - * -1 to disable. - * - * @unit m - * @min -1 - * @decimal 0 - * @increment 1 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_THR_LOW_HGT, -1.f); - -/* - * TECS parameters - * - */ - -/** - * Maximum descent rate - * - * @unit m/s - * @min 1.0 - * @max 15.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); - -/** - * Throttle damping factor - * - * This is the damping gain for the throttle demand loop. - * - * @min 0.0 - * @max 1.0 - * @decimal 3 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_THR_DAMPING, 0.05f); - -/** - * Integrator gain throttle - * - * Increase it to trim out speed and height offsets faster, - * with the downside of possible overshoots and oscillations. - * - * @min 0.0 - * @max 1.0 - * @decimal 3 - * @increment 0.005 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_THR_INTEG, 0.02f); - -/** - * Integrator gain pitch - * - * Increase it to trim out speed and height offsets faster, - * with the downside of possible overshoots and oscillations. - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.05 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f); - -/** - * Maximum vertical acceleration - * - * This is the maximum vertical acceleration - * either up or down that the controller will use to correct speed - * or height errors. - * - * @unit m/s^2 - * @min 1.0 - * @max 10.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); - -/** - * Airspeed measurement standard deviation - * - * For the airspeed filter in TECS. - * - * @unit m/s - * @min 0.01 - * @max 10.0 - * @decimal 2 - * @increment 0.1 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.07f); - -/** - * Airspeed rate measurement standard deviation - * - * For the airspeed filter in TECS. - * - * @unit m/s^2 - * @min 0.01 - * @max 10.0 - * @decimal 2 - * @increment 0.1 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SPD_DEV_STD, 0.2f); - -/** - * Process noise standard deviation for the airspeed rate - * - * This is defining the noise in the airspeed rate for the constant airspeed rate model - * of the TECS airspeed filter. - * - * @unit m/s^2 - * @min 0.01 - * @max 10.0 - * @decimal 2 - * @increment 0.1 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SPD_PRC_STD, 0.2f); - - -/** - * Roll -> Throttle feedforward - * - * Is used to compensate for the additional drag created by turning. - * Increase this gain if the aircraft initially loses energy in turns - * and reduce if the aircraft initially gains energy in turns. - * - * @min 0.0 - * @max 20.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); - /** * Speed <--> Altitude weight * @@ -590,75 +369,6 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); */ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); -/** - * Pitch damping gain - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.1 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f); - -/** - * Altitude error time constant. - * - * @min 2.0 - * @decimal 2 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f); - -/** - * Fast descend: minimum altitude error - * - * Minimum altitude error needed to descend with max airspeed and minimal throttle. - * A negative value disables fast descend. - * - * @min -1.0 - * @decimal 0 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_F_ALT_ERR, -1.0f); - -/** - * Height rate feed forward - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.3f); - -/** - * True airspeed error time constant. - * - * @min 2.0 - * @decimal 2 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f); - -/** - * Minimum groundspeed - * - * The controller will increase the commanded airspeed to maintain - * this minimum groundspeed to the next waypoint. - * - * @unit m/s - * @min 0.0 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); - /** * Custom stick configuration * @@ -672,31 +382,6 @@ PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); */ PARAM_DEFINE_INT32(FW_POS_STK_CONF, 2); -/** - * Specific total energy rate first order filter time constant. - * - * This filter is applied to the specific total energy rate used for throttle damping. - * - * @min 0.0 - * @max 2 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_STE_R_TC, 0.4f); - -/** - * Specific total energy balance rate feedforward gain. - * - * - * @min 0.5 - * @max 3 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f); - /** * Default target climbrate. * @@ -886,20 +571,6 @@ PARAM_DEFINE_INT32(FW_LND_NUDGE, 2); */ PARAM_DEFINE_INT32(FW_LND_ABORT, 3); -/** - * Wind-based airspeed scaling factor - * - * Multiplying this factor with the current absolute wind estimate gives the airspeed offset - * added to the minimum airspeed setpoint limit. This helps to make the - * system more robust against disturbances (turbulence) in high wind. - * - * @min 0 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_WIND_ARSP_SC, 0.f); - /** * Fixed-wing launch detection * diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 544ecae871..691c57adb4 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -94,7 +94,6 @@ void LoggedTopics::add_default_topics() add_topic("mission_result"); add_topic("navigator_mission_item"); add_topic("navigator_status"); - add_topic("npfg_status", 100); add_topic("offboard_control_mode", 100); add_topic("onboard_computer_status", 10); add_topic("parameter_update"); @@ -149,6 +148,12 @@ void LoggedTopics::add_default_topics() add_topic("vehicle_status"); add_optional_topic("vtol_vehicle_status", 200); add_topic("wind", 1000); + add_topic("fixed_wing_lateral_setpoint"); + add_topic("fixed_wing_longitudinal_setpoint"); + add_topic("longitudinal_control_configuration"); + add_topic("lateral_control_configuration"); + add_optional_topic("fixed_wing_lateral_guidance_status", 100); + add_optional_topic("fixed_wing_lateral_status", 100); // multi topics add_optional_topic_multi("actuator_outputs", 100, 3); diff --git a/src/modules/zenoh/Kconfig.topics b/src/modules/zenoh/Kconfig.topics index ac96b8586f..5ecde816d1 100644 --- a/src/modules/zenoh/Kconfig.topics +++ b/src/modules/zenoh/Kconfig.topics @@ -445,10 +445,6 @@ menu "Zenoh publishers/subscribers" bool "normalized_unsigned_setpoint" default n - config ZENOH_PUBSUB_NPFG_STATUS - bool "npfg_status" - default n - config ZENOH_PUBSUB_OBSTACLE_DISTANCE bool "obstacle_distance" default n From 0276f66b183ab38091640d2c7fc536bc0ba8907c Mon Sep 17 00:00:00 2001 From: Silvan Date: Wed, 16 Apr 2025 13:05:00 +0200 Subject: [PATCH 033/130] TECS: harden interface for NAN altitude input Signed-off-by: Silvan --- src/lib/tecs/TECS.cpp | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index 6a09b87759..e519246099 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -172,7 +172,12 @@ void TECSAltitudeReferenceModel::update(const float dt, const AltitudeReferenceS bool control_altitude = true; float altitude_setpoint = setpoint.alt; - if (PX4_ISFINITE(setpoint.alt_rate)) { + if (!PX4_ISFINITE(setpoint.alt) && !PX4_ISFINITE(setpoint.alt_rate)) { + // neither altitude nor altitude rate is set - reset to current altitude + _velocity_control_traj_generator.reset(0.f, 0, current_alt); + altitude_setpoint = current_alt; + + } else if (PX4_ISFINITE(setpoint.alt_rate)) { // input is height rate (not altitude) _velocity_control_traj_generator.setCurrentPositionEstimate(current_alt); _velocity_control_traj_generator.update(dt, setpoint.alt_rate); @@ -180,6 +185,7 @@ void TECSAltitudeReferenceModel::update(const float dt, const AltitudeReferenceS control_altitude = PX4_ISFINITE(altitude_setpoint); // returns true if altitude is locked } else { + // input is altitude _velocity_control_traj_generator.reset(0, height_rate, altitude_setpoint); } @@ -710,7 +716,6 @@ void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_set float throttle_trim, float pitch_limit_min, float pitch_limit_max, float target_climbrate, float target_sinkrate, const float speed_deriv_forward, float hgt_rate, float hgt_rate_sp) { - // Calculate the time since last update (seconds) const hrt_abstime now(hrt_absolute_time()); const float dt = static_cast((now - _update_timestamp)) / 1_s; @@ -781,7 +786,9 @@ void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_set void TECS::_setFastDescend(const float alt_setpoint, const float alt) { - if (_control_flag.airspeed_enabled && (_fast_descend_alt_err > FLT_EPSILON) + // disable fast descend if we are close to the target altitude or the altitude setpoint is not finite + + if (PX4_ISFINITE(alt_setpoint) && _control_flag.airspeed_enabled && (_fast_descend_alt_err > FLT_EPSILON) && ((alt_setpoint + _fast_descend_alt_err) < alt)) { auto now = hrt_absolute_time(); @@ -792,7 +799,7 @@ void TECS::_setFastDescend(const float alt_setpoint, const float alt) _fast_descend = constrain(max(_fast_descend, static_cast(now - _enabled_fast_descend_timestamp) / static_cast(FAST_DESCEND_RAMP_UP_TIME)), 0.f, 1.f); - } else if ((_fast_descend > FLT_EPSILON) && (_fast_descend_alt_err > FLT_EPSILON)) { + } else if (PX4_ISFINITE(alt_setpoint) && (_fast_descend > FLT_EPSILON) && (_fast_descend_alt_err > FLT_EPSILON)) { // Were in fast descend, scale it down. up until 5m above target altitude _fast_descend = constrain((alt - alt_setpoint - 5.f) / _fast_descend_alt_err, 0.f, 1.f); _enabled_fast_descend_timestamp = 0U; From 3e3f10f5bc773afde11e3d0150a608928fbf7134 Mon Sep 17 00:00:00 2001 From: Silvan Date: Wed, 16 Apr 2025 13:09:09 +0200 Subject: [PATCH 034/130] VehicleAttitudeSetpoint.msg: remove reset_integral and fw_control_yaw_wheel Signed-off-by: Silvan --- docs/en/flight_modes_fw/takeoff.md | 3 +- .../msg/VehicleAttitudeSetpointV0.msg | 18 ++++++ .../translations/all_translations.h | 1 + ...translation_vehicle_attitude_setpoint_v1.h | 53 +++++++++++++++++ msg/versioned/VehicleAttitudeSetpoint.msg | 6 +- .../FixedwingAttitudeControl.cpp | 10 ++-- .../FixedwingAttitudeControl.hpp | 1 - .../runway_takeoff/RunwayTakeoff.cpp | 46 +++------------ .../runway_takeoff/RunwayTakeoff.h | 59 ++----------------- .../runway_takeoff/runway_takeoff_params.c | 27 --------- .../PositionControl/PositionControlTest.cpp | 2 - 11 files changed, 90 insertions(+), 136 deletions(-) create mode 100644 msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg create mode 100644 msg/translation_node/translations/translation_vehicle_attitude_setpoint_v1.h diff --git a/docs/en/flight_modes_fw/takeoff.md b/docs/en/flight_modes_fw/takeoff.md index ea82c74d60..b9e6d2e703 100644 --- a/docs/en/flight_modes_fw/takeoff.md +++ b/docs/en/flight_modes_fw/takeoff.md @@ -101,7 +101,7 @@ The _runway takeoff mode_ has the following phases: ::: info For a smooth takeoff, the runway wheel controller possibly needs to be tuned. -It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)) and an outer loop that calculates heading setpoints from course errors and can be tuned via [RWTO_NPFG_PERIOD](#RWTO_NPFG_PERIOD). +It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)). ::: ### Parameters (Runway Takeoff) @@ -120,7 +120,6 @@ Runway takeoff is affected by the following parameters: | [RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Enable wheel controller nudging while on the runway | | [FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | The wingspan of the vehicle. Used to prevent wingstrikes. | | [FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | The height of the wings above ground (ground clearance). Used to prevent wingstrikes. | -| [RWTO_NPFG_PERIOD](../advanced_config/parameter_reference.md#RWTO_NPFG_PERIOD) | L1 period while steering on runway. Increase for less aggressive response to course errors. | ## See Also diff --git a/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg b/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg new file mode 100644 index 0000000000..28aa780699 --- /dev/null +++ b/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg @@ -0,0 +1,18 @@ +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 yaw_sp_move_rate # rad/s (commanded by user) + +# For quaternion-based attitude control +float32[4] q_d # Desired quaternion for quaternion control + +# For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. +# For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. +float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] + +bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) + +bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) + +# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint diff --git a/msg/translation_node/translations/all_translations.h b/msg/translation_node/translations/all_translations.h index 7564a9f83d..21b128c03c 100644 --- a/msg/translation_node/translations/all_translations.h +++ b/msg/translation_node/translations/all_translations.h @@ -12,3 +12,4 @@ #include "translation_vehicle_status_v1.h" #include "translation_airspeed_validated_v1.h" +#include "translation_vehicle_attitude_setpoint_v1.h" diff --git a/msg/translation_node/translations/translation_vehicle_attitude_setpoint_v1.h b/msg/translation_node/translations/translation_vehicle_attitude_setpoint_v1.h new file mode 100644 index 0000000000..b30e469dff --- /dev/null +++ b/msg/translation_node/translations/translation_vehicle_attitude_setpoint_v1.h @@ -0,0 +1,53 @@ +/**************************************************************************** + * Copyright (c) 2025 PX4 Development Team. + * SPDX-License-Identifier: BSD-3-Clause + ****************************************************************************/ +#pragma once + +// Translate VehicleAttitudeSetpoint v0 <--> v1 +#include +#include + +class VehicleAttitudeSetpointV1Translation { +public: + using MessageOlder = px4_msgs_old::msg::VehicleAttitudeSetpointV0; + static_assert(MessageOlder::MESSAGE_VERSION == 0); + + using MessageNewer = px4_msgs::msg::VehicleAttitudeSetpoint; + static_assert(MessageNewer::MESSAGE_VERSION == 1); + + static constexpr const char* kTopic = "fmu/in/vehicle_attitude_setpoint"; + + static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { + // Set msg_newer from msg_older + msg_newer.timestamp = msg_older.timestamp; + msg_newer.yaw_sp_move_rate = msg_older.yaw_sp_move_rate; + msg_newer.q_d[0] = msg_older.q_d[0]; + msg_newer.q_d[1] = msg_older.q_d[1]; + msg_newer.q_d[2] = msg_older.q_d[2]; + msg_newer.q_d[3] = msg_older.q_d[3]; + msg_newer.thrust_body[0] = msg_older.thrust_body[0]; + msg_newer.thrust_body[1] = msg_older.thrust_body[1]; + msg_newer.thrust_body[2] = msg_older.thrust_body[2]; + + } + + static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { + // Set msg_older from msg_newer + msg_older.timestamp = msg_newer.timestamp; + msg_older.yaw_sp_move_rate = msg_newer.yaw_sp_move_rate; + msg_older.q_d[0] = msg_newer.q_d[0]; + msg_older.q_d[1] = msg_newer.q_d[1]; + msg_older.q_d[2] = msg_newer.q_d[2]; + msg_older.q_d[3] = msg_newer.q_d[3]; + msg_older.thrust_body[0] = msg_newer.thrust_body[0]; + msg_older.thrust_body[1] = msg_newer.thrust_body[1]; + msg_older.thrust_body[2] = msg_newer.thrust_body[2]; + + msg_older.reset_integral = false; + msg_older.fw_control_yaw_wheel = false; + + } +}; + +REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleAttitudeSetpointV1Translation); diff --git a/msg/versioned/VehicleAttitudeSetpoint.msg b/msg/versioned/VehicleAttitudeSetpoint.msg index 28aa780699..b32b336edb 100644 --- a/msg/versioned/VehicleAttitudeSetpoint.msg +++ b/msg/versioned/VehicleAttitudeSetpoint.msg @@ -1,4 +1,4 @@ -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # time since system start (microseconds) @@ -11,8 +11,4 @@ float32[4] q_d # Desired quaternion for quaternion control # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] -bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) - -bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) - # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp index 9057d792b9..c9a6d921fc 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp @@ -108,8 +108,6 @@ FixedwingAttitudeControl::vehicle_manual_poll(const float yaw_body) const Quatf q(Eulerf(roll_body, pitch_body, yaw_body)); q.copyTo(_att_sp.q_d); - _att_sp.reset_integral = false; - _att_sp.timestamp = hrt_absolute_time(); _attitude_sp_pub.publish(_att_sp); @@ -271,7 +269,8 @@ void FixedwingAttitudeControl::Run() bool wheel_control = false; - if (_param_fw_w_en.get() && _att_sp.fw_control_yaw_wheel && _vcontrol_mode.flag_control_auto_enabled) { + // TODO listen to a runway_takeoff_status to determine when to control wheel + if (_param_fw_w_en.get() && _vcontrol_mode.flag_control_auto_enabled) { wheel_control = true; } @@ -283,11 +282,10 @@ void FixedwingAttitudeControl::Run() if (_vcontrol_mode.flag_control_rates_enabled) { - /* Reset integrators if commanded by attitude setpoint, or the aircraft is on ground + /* Reset integrators if the aircraft is on ground * or a multicopter (but not transitioning VTOL or tailsitter) */ - if (_att_sp.reset_integral - || _landed + if (_landed || !_in_fw_or_transition_wo_tailsitter_transition) { _rates_sp.reset_integral = true; diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp index 6c902878e1..43432a4a3a 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp @@ -132,7 +132,6 @@ private: DEFINE_PARAMETERS( (ParamFloat) _param_fw_airspd_max, - (ParamFloat) _param_fw_airspd_min, (ParamFloat) _param_fw_airspd_stall, (ParamFloat) _param_fw_airspd_trim, (ParamBool) _param_fw_use_airspd, diff --git a/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.cpp b/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.cpp index 7cfc23b438..498a5332b1 100644 --- a/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.cpp +++ b/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.cpp @@ -51,10 +51,8 @@ using namespace time_literals; namespace runwaytakeoff { -void RunwayTakeoff::init(const hrt_abstime &time_now, const float initial_yaw, const matrix::Vector2d &start_pos_global) +void RunwayTakeoff::init(const hrt_abstime &time_now) { - initial_yaw_ = initial_yaw; - start_pos_global_ = start_pos_global; takeoff_state_ = RunwayTakeoffState::THROTTLE_RAMP; initialized_ = true; time_initialized_ = time_now; @@ -99,42 +97,26 @@ void RunwayTakeoff::update(const hrt_abstime &time_now, const float takeoff_airs } } -bool RunwayTakeoff::controlYaw() -{ - // keep controlling yaw directly until we start navigation - return takeoff_state_ < RunwayTakeoffState::CLIMBOUT; -} - -float RunwayTakeoff::getPitch(float external_pitch_setpoint) +float RunwayTakeoff::getPitch() { if (takeoff_state_ <= RunwayTakeoffState::CLAMPED_TO_RUNWAY) { return math::radians(param_rwto_psp_.get()); } - return external_pitch_setpoint; + return NAN; } -float RunwayTakeoff::getRoll(float external_roll_setpoint) +float RunwayTakeoff::getRoll() { // until we have enough ground clearance, set roll to 0 if (takeoff_state_ < RunwayTakeoffState::CLIMBOUT) { return 0.0f; } - return external_roll_setpoint; + return NAN; } -float RunwayTakeoff::getYaw(float external_yaw_setpoint) -{ - if (param_rwto_hdg_.get() == 0 && takeoff_state_ < RunwayTakeoffState::CLIMBOUT) { - return initial_yaw_; - - } else { - return external_yaw_setpoint; - } -} - -float RunwayTakeoff::getThrottle(const float idle_throttle, const float external_throttle_setpoint) const +float RunwayTakeoff::getThrottle(const float idle_throttle) const { float throttle = idle_throttle; @@ -147,30 +129,18 @@ float RunwayTakeoff::getThrottle(const float idle_throttle, const float external break; case RunwayTakeoffState::CLAMPED_TO_RUNWAY: + case RunwayTakeoffState::CLIMBOUT: throttle = param_rwto_max_thr_.get(); break; - case RunwayTakeoffState::CLIMBOUT: - // ramp in throttle setpoint over takeoff rotation transition time - throttle = interpolateValuesOverAbsoluteTime(param_rwto_max_thr_.get(), external_throttle_setpoint, takeoff_time_, - param_rwto_rot_time_.get()); - - break; - case RunwayTakeoffState::FLY: - throttle = external_throttle_setpoint; + throttle = NAN; } return throttle; } -bool RunwayTakeoff::resetIntegrators() -{ - // reset integrators if we're still on runway - return takeoff_state_ < RunwayTakeoffState::CLIMBOUT; -} - float RunwayTakeoff::getMinPitch(float min_pitch_in_climbout, float min_pitch) const { if (takeoff_state_ < RunwayTakeoffState::CLIMBOUT) { diff --git a/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.h b/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.h index 35e463077e..22fa8a51ec 100644 --- a/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.h +++ b/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.h @@ -70,10 +70,8 @@ public: * @brief Initializes the state machine. * * @param time_now Absolute time since system boot [us] - * @param initial_yaw Vehicle yaw angle at time of initialization [us] - * @param start_pos_global Vehicle global (lat, lon) position at time of initialization [deg] */ - void init(const hrt_abstime &time_now, const float initial_yaw, const matrix::Vector2d &start_pos_global); + void init(const hrt_abstime &time_now); /** * @brief Updates the state machine based on the current vehicle condition. @@ -103,37 +101,14 @@ public: bool runwayTakeoffEnabled() { return param_rwto_tkoff_.get(); } /** - * @return Initial vehicle yaw angle [rad] - */ - float getInitYaw() { return initial_yaw_; } - - /** - * @return The vehicle should control yaw via rudder or nose gear - */ - bool controlYaw(); - - /** - * @param external_pitch_setpoint Externally commanded pitch angle setpoint (usually from TECS) [rad] * @return Pitch angle setpoint (limited while plane is on runway) [rad] */ - float getPitch(float external_pitch_setpoint); + float getPitch(); /** - * @param external_roll_setpoint Externally commanded roll angle setpoint (usually from path navigation) [rad] * @return Roll angle setpoint [rad] */ - float getRoll(float external_roll_setpoint); - - /** - * @brief Returns the appropriate yaw angle setpoint. - * - * In heading hold mode (_heading_mode == 0), it returns initial yaw as long as it's on the runway. - * When it has enough ground clearance we start navigation towards WP. - * - * @param external_yaw_setpoint Externally commanded yaw angle setpoint [rad] - * @return Yaw angle setpoint [rad] - */ - float getYaw(float external_yaw_setpoint); + float getRoll(); /** * @brief Returns the throttle setpoint. @@ -142,10 +117,9 @@ public: * ramps from RWTO_MAX_THR to the externally defined throttle setting over the takeoff rotation time * * @param idle_throttle normalized [0,1] - * @param external_throttle_setpoint Externally commanded throttle setpoint (usually from TECS), normalized [0,1] * @return Throttle setpoint, normalized [0,1] */ - float getThrottle(const float idle_throttle, const float external_throttle_setpoint) const; + float getThrottle(const float idle_throttle) const; /** * @param min_pitch_in_climbout Minimum pitch angle during climbout [rad] @@ -160,20 +134,9 @@ public: */ float getMaxPitch(const float max_pitch) const; - /** - * @return Runway takeoff starting position in global frame (lat, lon) [deg] - */ - const matrix::Vector2d &getStartPosition() const { return start_pos_global_; }; - // NOTE: this is only to be used for mistaken mode transitions to takeoff while already in air void forceSetFlyState() { takeoff_state_ = RunwayTakeoffState::FLY; } - /** - * @return If the attitude / rate control integrators should be continually reset. - * This is the case during ground roll. - */ - bool resetIntegrators(); - /** * @brief Reset the state machine. */ @@ -212,22 +175,8 @@ private: */ hrt_abstime takeoff_time_{0}; - /** - * Initial yaw of the vehicle on first pass through the runway takeoff state machine. - * used for heading hold mode. [rad] - */ - float initial_yaw_{0.f}; - - /** - * The global (lat, lon) position of the vehicle on first pass through the runway takeoff state machine. The - * takeoff path emanates from this point to correct for any GNSS uncertainty from the planned takeoff point. The - * vehicle should accordingly be set on the center of the runway before engaging the mission. [deg] - */ - matrix::Vector2d start_pos_global_{}; - DEFINE_PARAMETERS( (ParamBool) param_rwto_tkoff_, - (ParamInt) param_rwto_hdg_, (ParamFloat) param_rwto_max_thr_, (ParamFloat) param_rwto_psp_, (ParamFloat) param_rwto_ramp_time_, diff --git a/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c b/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c index 766cd8f54e..e33fa9d616 100644 --- a/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c +++ b/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c @@ -47,21 +47,6 @@ */ PARAM_DEFINE_INT32(RWTO_TKOFF, 0); -/** - * Specifies which heading should be held during the runway takeoff ground roll. - * - * 0: airframe heading when takeoff is initiated - * 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF - * position defined by operator) - * - * @value 0 Airframe - * @value 1 Runway - * @min 0 - * @max 1 - * @group Runway Takeoff - */ -PARAM_DEFINE_INT32(RWTO_HDG, 0); - /** * Max throttle during runway takeoff. * @@ -102,18 +87,6 @@ PARAM_DEFINE_FLOAT(RWTO_PSP, 0.0); */ PARAM_DEFINE_FLOAT(RWTO_RAMP_TIME, 2.0f); -/** - * NPFG period while steering on runway - * - * @unit s - * @min 1.0 - * @max 100.0 - * @decimal 1 - * @increment 0.1 - * @group Runway Takeoff - */ -PARAM_DEFINE_FLOAT(RWTO_NPFG_PERIOD, 5.0f); - /** * Enable use of yaw stick for nudging the wheel during runway ground roll * diff --git a/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp b/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp index 9c1e72b1a5..253f80960f 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControlTest.cpp @@ -63,8 +63,6 @@ TEST(PositionControlTest, EmptySetpoint) EXPECT_FLOAT_EQ(attitude.yaw_sp_move_rate, 0.f); EXPECT_EQ(Quatf(attitude.q_d), Quatf(1.f, 0.f, 0.f, 0.f)); EXPECT_EQ(Vector3f(attitude.thrust_body), Vector3f(0.f, 0.f, 0.f)); - EXPECT_EQ(attitude.reset_integral, false); - EXPECT_EQ(attitude.fw_control_yaw_wheel, false); } class PositionControlBasicTest : public ::testing::Test From 0ea109ff5dc50b7f2559a298429e4c95439f77f1 Mon Sep 17 00:00:00 2001 From: Silvan Date: Thu, 27 Mar 2025 23:29:36 +0100 Subject: [PATCH 035/130] perfromance model: add FW_AIRSPD_FLP_SC to reduce with flaps Signed-off-by: Silvan --- docs/en/flight_modes_fw/land.md | 1 + docs/en/flight_modes_fw/takeoff.md | 1 + src/lib/fw_performance_model/PerformanceModel.cpp | 11 ++++++----- src/lib/fw_performance_model/PerformanceModel.hpp | 12 ++++++++---- .../fw_performance_model/performance_model_params.c | 13 +++++++++++++ src/lib/npfg/CourseToAirspeedRefMapper.hpp | 12 ------------ .../FwLateralLongitudinalControl.cpp | 11 +++++++++-- .../FwLateralLongitudinalControl.hpp | 4 ++++ .../fw_pos_control/FixedwingPositionControl.cpp | 13 ------------- .../fw_pos_control/FixedwingPositionControl.hpp | 1 - 10 files changed, 42 insertions(+), 37 deletions(-) diff --git a/docs/en/flight_modes_fw/land.md b/docs/en/flight_modes_fw/land.md index 3c294e95f0..43d8ff9294 100644 --- a/docs/en/flight_modes_fw/land.md +++ b/docs/en/flight_modes_fw/land.md @@ -45,6 +45,7 @@ Land mode behaviour can be configured using the parameters below. | [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | | [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | | [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. ## See Also diff --git a/docs/en/flight_modes_fw/takeoff.md b/docs/en/flight_modes_fw/takeoff.md index b9e6d2e703..a59413394d 100644 --- a/docs/en/flight_modes_fw/takeoff.md +++ b/docs/en/flight_modes_fw/takeoff.md @@ -50,6 +50,7 @@ Parameters that affect both catapult/hand-launch and runway takeoffs: | [FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | This is the minimum pitch angle setpoint during the climbout phase | | [FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Maximum climb rate. | | [FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Flaps setpoint during takeoff | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_TKO_AIRSPD is below FW_AIRSPD_MIN. | ::: info The vehicle always respects normal FW max/min throttle settings during takeoff ([FW_THR_MIN](../advanced_config/parameter_reference.md#FW_THR_MIN), [FW_THR_MAX](../advanced_config/parameter_reference.md#FW_THR_MAX)). diff --git a/src/lib/fw_performance_model/PerformanceModel.cpp b/src/lib/fw_performance_model/PerformanceModel.cpp index 6fb315cb89..e946347a44 100644 --- a/src/lib/fw_performance_model/PerformanceModel.cpp +++ b/src/lib/fw_performance_model/PerformanceModel.cpp @@ -144,17 +144,18 @@ float PerformanceModel::getCalibratedTrimAirspeed() const return math::constrain(_param_fw_airspd_trim.get() * sqrtf(getWeightRatio()), _param_fw_airspd_min.get(), _param_fw_airspd_max.get()); } -float PerformanceModel::getMinimumCalibratedAirspeed(float load_factor) const +float PerformanceModel::getMinimumCalibratedAirspeed(float load_factor, float flaps_setpoint) const { - load_factor = math::max(load_factor, FLT_EPSILON); - return _param_fw_airspd_min.get() * sqrtf(getWeightRatio() * load_factor); + const float airspeed_flap_factor = math::lerp(1.f, _param_fw_airspd_flp_sc.get(), flaps_setpoint); + return (_param_fw_airspd_min.get() * airspeed_flap_factor) * sqrtf(getWeightRatio() * load_factor); } -float PerformanceModel::getCalibratedStallAirspeed(float load_factor) const +float PerformanceModel::getCalibratedStallAirspeed(float load_factor, float flaps_setpoint) const { load_factor = math::max(load_factor, FLT_EPSILON); - return _param_fw_airspd_stall.get() * sqrtf(getWeightRatio() * load_factor); + const float airspeed_flap_factor = math::lerp(1.f, _param_fw_airspd_flp_sc.get(), flaps_setpoint); + return (_param_fw_airspd_stall.get() * airspeed_flap_factor) * sqrtf(getWeightRatio() * load_factor); } float PerformanceModel::getMaximumCalibratedAirspeed() const diff --git a/src/lib/fw_performance_model/PerformanceModel.hpp b/src/lib/fw_performance_model/PerformanceModel.hpp index fbdd8693c2..dece1bb3e0 100644 --- a/src/lib/fw_performance_model/PerformanceModel.hpp +++ b/src/lib/fw_performance_model/PerformanceModel.hpp @@ -94,11 +94,12 @@ public: float getCalibratedTrimAirspeed() const; /** - * Get the minimum airspeed compensated for weight and load factor due to bank angle. + * Get the minimum airspeed compensated for weight, load factor due to bank angle and flaps. * @param load_factor due to banking + * @param flaps_setpoint Flaps setpoint, normalized in range [0,1] * @return calibrated minimum airspeed in m/s */ - float getMinimumCalibratedAirspeed(float load_factor = 1.0f) const; + float getMinimumCalibratedAirspeed(float load_factor, float flaps_setpoint) const; /** * Get the maximum airspeed. @@ -109,9 +110,10 @@ public: /** * get the stall airspeed compensated for load factor due to bank angle. * @param load_factor load factor due to banking + * @param flaps_setpoint Flaps setpoint, normalized in range [0,1] * @return calibrated stall airspeed in m/s */ - float getCalibratedStallAirspeed(float load_factor) const; + float getCalibratedStallAirspeed(float load_factor, float flaps_setpoint) const; /** * Run some checks on parameters and detect unfeasible combinations. @@ -134,7 +136,9 @@ private: (ParamFloat) _param_fw_thr_max, (ParamFloat) _param_fw_thr_min, (ParamFloat) _param_fw_thr_aspd_min, - (ParamFloat) _param_fw_thr_aspd_max) + (ParamFloat) _param_fw_thr_aspd_max, + (ParamFloat) _param_fw_airspd_flp_sc + ) /** * Get the sea level trim throttle for a given calibrated airspeed setpoint. diff --git a/src/lib/fw_performance_model/performance_model_params.c b/src/lib/fw_performance_model/performance_model_params.c index 0c39d2ed39..2223f60139 100644 --- a/src/lib/fw_performance_model/performance_model_params.c +++ b/src/lib/fw_performance_model/performance_model_params.c @@ -212,3 +212,16 @@ PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 10.0f); * @group FW Performance */ PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 20.0f); + +/** + * Airspeed scale with full flaps + * + * Factor applied to the minimum and stall airspeed when flaps are fully deployed. + * + * @min 0.5 + * @max 1 + * @decimal 2 + * @increment 0.01 + * @group FW Performance + */ +PARAM_DEFINE_FLOAT(FW_AIRSPD_FLP_SC, 1.f); diff --git a/src/lib/npfg/CourseToAirspeedRefMapper.hpp b/src/lib/npfg/CourseToAirspeedRefMapper.hpp index 70f3312e9b..65d8e7ae81 100644 --- a/src/lib/npfg/CourseToAirspeedRefMapper.hpp +++ b/src/lib/npfg/CourseToAirspeedRefMapper.hpp @@ -77,18 +77,6 @@ public: const matrix::Vector2f &wind_vel, float max_airspeed, float min_ground_speed) const; private: - /* - * Determines a reference air velocity *without curvature compensation, but - * including "optimal" true airspeed reference compensation in excess wind conditions. - * Nominal and maximum true airspeed member variables must be set before using this method. - * - * @param[in] wind_vel Wind velocity vector [m/s] - * @param[in] bearing_setpoint Bearing - * @param[in] airspeed_true True airspeed setpoint[m/s] - * @return Air velocity vector [m/s] - */ - matrix::Vector2f refAirVelocity(const matrix::Vector2f &wind_vel, const float bearing_setpoint, - float airspeed_true, float min_ground_speed) const; /* * Projection of the air velocity vector onto the bearing line considering * a connected wind triangle. diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp index eb92670ffa..77e0ae5b23 100644 --- a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp @@ -92,7 +92,7 @@ FwLateralLongitudinalControl::parameters_update() _tecs.set_max_sink_rate(_param_fw_t_sink_max.get()); _tecs.set_min_sink_rate(_performance_model.getMinimumSinkRate(_air_density)); _tecs.set_equivalent_airspeed_trim(_performance_model.getCalibratedTrimAirspeed()); - _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed()); + _tecs.set_equivalent_airspeed_min(_performance_model.getMinimumCalibratedAirspeed(getLoadFactor(), _flaps_setpoint)); _tecs.set_equivalent_airspeed_max(_performance_model.getMaximumCalibratedAirspeed()); _tecs.set_throttle_damp(_param_fw_t_thr_damping.get()); _tecs.set_integrator_gain_throttle(_param_fw_t_thr_integ.get()); @@ -168,6 +168,13 @@ void FwLateralLongitudinalControl::Run() _vehicle_status_sub.update(); _control_mode_sub.update(); + + if (_flaps_setpoint_sub.updated()) { + normalized_unsigned_setpoint_s flaps_setpoint{}; + _flaps_setpoint_sub.copy(&flaps_setpoint); + _flaps_setpoint = flaps_setpoint.normalized_setpoint; + } + update_control_state(); if (_control_mode_sub.get().flag_control_manual_enabled && _control_mode_sub.get().flag_control_altitude_enabled @@ -622,7 +629,7 @@ float FwLateralLongitudinalControl::adapt_airspeed_setpoint(const float control_interval, float calibrated_airspeed_setpoint, float calibrated_min_airspeed_guidance, float wind_speed) { - float system_min_airspeed = _performance_model.getMinimumCalibratedAirspeed(getLoadFactor()); + float system_min_airspeed = _performance_model.getMinimumCalibratedAirspeed(getLoadFactor(), _flaps_setpoint); const float system_max_airspeed = _performance_model.getMaximumCalibratedAirspeed(); diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp index 703fb722e9..590054ae89 100644 --- a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp @@ -66,6 +66,7 @@ #include #include #include +#include #include #include #include @@ -110,6 +111,7 @@ private: uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _airspeed_validated_sub{ORB_ID(airspeed_validated)}; + uORB::Subscription _flaps_setpoint_sub{ORB_ID(flaps_setpoint)}; uORB::Subscription _wind_sub{ORB_ID(wind)}; uORB::SubscriptionData _control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::SubscriptionData _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; @@ -127,6 +129,8 @@ private: fixed_wing_lateral_setpoint_s _lat_control_sp{empty_lateral_control_setpoint}; lateral_control_configuration_s _lateral_configuration{}; + float _flaps_setpoint{0.f}; + uORB::Publication _attitude_sp_pub; uORB::Publication _tecs_status_pub{ORB_ID(tecs_status)}; uORB::PublicationData _flight_phase_estimation_pub{ORB_ID(flight_phase_estimation)}; diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 328a556be2..672a718dc8 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -2591,19 +2591,6 @@ fw_pos_control is the fixed-wing position controller. return 0; } -float FixedwingPositionControl::getLoadFactor() const -{ - float load_factor_from_bank_angle = 1.0f; - - float roll_body = Eulerf(Quatf(_att_sp.q_d)).phi(); - - if (PX4_ISFINITE(roll_body)) { - load_factor_from_bank_angle = 1.0f / math::max(cosf(roll_body), FLT_EPSILON); - } - - return load_factor_from_bank_angle; - -} extern "C" __EXPORT int fw_pos_control_main(int argc, char *argv[]) { diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index e7526dca40..aea0dd5a89 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -424,7 +424,6 @@ private: void landing_status_publish(); void publishLocalPositionSetpoint(const position_setpoint_s ¤t_waypoint); - float getLoadFactor() const; /** * @brief Sets the landing abort status and publishes landing status. From 817b0191e768e5044c31fb49b273779ac137190b Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Wed, 16 Apr 2025 15:57:34 +0200 Subject: [PATCH 036/130] NPFG: add unit tests and add back feasible bearing check back --- src/lib/npfg/CMakeLists.txt | 1 + src/lib/npfg/CourseToAirspeedRefMapper.cpp | 31 +- src/lib/npfg/NpfgTest.cpp | 368 +++++++++++++++++++++ 3 files changed, 388 insertions(+), 12 deletions(-) create mode 100644 src/lib/npfg/NpfgTest.cpp diff --git a/src/lib/npfg/CMakeLists.txt b/src/lib/npfg/CMakeLists.txt index d5da8fb2f2..6e34a9a590 100644 --- a/src/lib/npfg/CMakeLists.txt +++ b/src/lib/npfg/CMakeLists.txt @@ -41,3 +41,4 @@ px4_add_library(npfg ) target_link_libraries(npfg PRIVATE geo) +px4_add_unit_gtest(SRC NpfgTest.cpp LINKLIBS npfg) diff --git a/src/lib/npfg/CourseToAirspeedRefMapper.cpp b/src/lib/npfg/CourseToAirspeedRefMapper.cpp index 7e745486b4..170348f139 100644 --- a/src/lib/npfg/CourseToAirspeedRefMapper.cpp +++ b/src/lib/npfg/CourseToAirspeedRefMapper.cpp @@ -40,11 +40,18 @@ CourseToAirspeedRefMapper::mapCourseSetpointToHeadingSetpoint(const float bearin { const Vector2f bearing_vector = Vector2f{cosf(bearing_setpoint), sinf(bearing_setpoint)}; const float wind_cross_bearing = wind_vel.cross(bearing_vector); + const float wind_dot_bearing = wind_vel.dot(bearing_vector); - const float airsp_dot_bearing = projectAirspOnBearing(airspeed_sp, wind_cross_bearing); - const Vector2f air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vector); + Vector2f air_vel_ref; - // TODO check if we need to use infeasibleAirVelRef or other mitigation functions in some cases (high wind) + if (bearingIsFeasible(wind_cross_bearing, wind_dot_bearing, airspeed_sp, wind_vel.norm())) { + + const float airsp_dot_bearing = projectAirspOnBearing(airspeed_sp, wind_cross_bearing); + air_vel_ref = solveWindTriangle(wind_cross_bearing, airsp_dot_bearing, bearing_vector); + + } else { + air_vel_ref = infeasibleAirVelRef(wind_vel, bearing_vector, wind_vel.norm(), airspeed_sp); + } return atan2f(air_vel_ref(1), air_vel_ref(0)); } @@ -96,12 +103,12 @@ CourseToAirspeedRefMapper::solveWindTriangle(const float wind_cross_bearing, con wind_cross_bearing * bearing_vec(0) + airsp_dot_bearing * bearing_vec(1)}; } -// matrix::Vector2f CourseToAirspeedRefMapper::infeasibleAirVelRef(const Vector2f &wind_vel, const Vector2f &bearing_vec, -// const float wind_speed, const float airspeed) const -// { -// // NOTE: wind speed must be greater than airspeed, and airspeed must be greater than zero to use this function -// // it is assumed that bearing feasibility is checked and found infeasible (e.g. bearingIsFeasible() = false) prior to entering this method -// // otherwise the normalization of the air velocity vector could have a division by zero -// Vector2f air_vel_ref = sqrtf(math::max(wind_speed * wind_speed - airspeed * airspeed, 0.0f)) * bearing_vec - wind_vel; -// return air_vel_ref.normalized() * airspeed; -// } +matrix::Vector2f CourseToAirspeedRefMapper::infeasibleAirVelRef(const Vector2f &wind_vel, const Vector2f &bearing_vec, + const float wind_speed, const float airspeed) const +{ + // NOTE: wind speed must be greater than airspeed, and airspeed must be greater than zero to use this function + // it is assumed that bearing feasibility is checked and found infeasible (e.g. bearingIsFeasible() = false) prior to entering this method + // otherwise the normalization of the air velocity vector could have a division by zero + Vector2f air_vel_ref = sqrtf(math::max(wind_speed * wind_speed - airspeed * airspeed, 0.0f)) * bearing_vec - wind_vel; + return air_vel_ref.normalized() * airspeed; +} diff --git a/src/lib/npfg/NpfgTest.cpp b/src/lib/npfg/NpfgTest.cpp new file mode 100644 index 0000000000..767fcf69b9 --- /dev/null +++ b/src/lib/npfg/NpfgTest.cpp @@ -0,0 +1,368 @@ + +/**************************************************************************** + * + * Copyright (C) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/****************************************************************** + * Test code for the NPFG algorithm + * Run this test only using "make tests TESTFILTER=Npfg" + * + * + * NOTE: + * + * +******************************************************************/ + +#include +#include +#include + +using namespace matrix; + +TEST(NpfgTest, NoWind) +{ + CourseToAirspeedRefMapper _course_to_airspeed; + + // GIVEN + const Vector2f wind_vel(0.f, 0.f); + float bearing = 0.f; + float airspeed_max = 20.f; + float min_ground_speed = 5.0f; + float airspeed_setpoint = 15.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + float min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + float airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + float heading_setpoint = _course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted); + + // THEN: expect heading due North with a min airspeed equal to min_ground_speed + EXPECT_NEAR(heading_setpoint, 0.f, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, min_ground_speed, FLT_EPSILON); + + // GIVEN: bearing due East + bearing = M_PI_2_F; + airspeed_max = 20.f; + min_ground_speed = 5.0f; + + // WHEN: we update bearing and airspeed magnitude augmentation + min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + + // THEN: expect heading due East with a min airspeed equal to min_ground_speed + EXPECT_NEAR(heading_setpoint, M_PI_2_F, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, min_ground_speed, FLT_EPSILON); +} + +TEST(NpfgTest, LightCrossWind) +{ + CourseToAirspeedRefMapper _course_to_airspeed; + + // GIVEN + const Vector2f wind_vel(0.f, 6.f); + float bearing = 0.f; + float airspeed_max = 20.f; + float min_ground_speed = 5.0f; + float airspeed_setpoint = 15.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + float min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + float airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + float heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading -0.4115168 with a min airspeed of to 7.8 (sqrt(25+36)) + EXPECT_NEAR(heading_setpoint, -0.4115168, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, 7.8f, 0.1f); + + // GIVEN: bearing due South + bearing = M_PI_F; + airspeed_max = 20.f; + min_ground_speed = 5.0f; + + // WHEN: we update bearing and airspeed magnitude augmentation + min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading of -2.73 and a min airspeed of 7.8 (sqrt(25+36)) + EXPECT_NEAR(heading_setpoint, -2.73f, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, 7.8f, 0.1f); +} + +TEST(NpfgTest, StrongHeadWind) +{ + CourseToAirspeedRefMapper _course_to_airspeed; + + // GIVEN: bearing due North and wind from the North + const Vector2f wind_vel(-16.f, 0.f); + float bearing = 0.f; + float airspeed_max = 25.f; + float min_ground_speed = 5.0f; + float airspeed_setpoint = 15.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + float min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + float airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + float heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading due North with a min airspeed equal to 16+min_ground_speed + EXPECT_NEAR(heading_setpoint, 0.f, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, 16 + min_ground_speed, 0.1f); +} + +TEST(NpfgTest, StrongTailWind) +{ + CourseToAirspeedRefMapper _course_to_airspeed; + + // GIVEN: bearing due East and wind from the West + const Vector2f wind_vel(0.f, 16.f); + float bearing = M_PI_2_F; + float airspeed_max = 25.f; + float min_ground_speed = 5.0f; + float airspeed_setpoint = 15.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + float min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + float airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + float heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading due East with a min airspeed at 0 + EXPECT_NEAR(heading_setpoint, M_PI_2_F, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, 0.f, 0.1f); +} + +TEST(NpfgTest, ExcessHeadWind) +{ + // TEST DESCRIPTION: infeasible bearing, with |wind| = |airspeed|. Align with wind + + CourseToAirspeedRefMapper _course_to_airspeed; + + // GIVEN: bearing due North and wind from the North + const Vector2f wind_vel(-25.f, 0.f); + float bearing = 0.f; + float airspeed_max = 25.f; + float min_ground_speed = 5.0f; + float airspeed_setpoint = 15.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + float min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + float airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + float heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading sp due North with a min airspeed equal to airspeed_max + EXPECT_NEAR(heading_setpoint, 0.f, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, airspeed_max, 0.1f); + + // WHEN: we increase the maximum airspeed + airspeed_max = 35.f; + + min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + // THEN: expect the minimum airspeed to be high enough to maintain minimum groundspeed + EXPECT_NEAR(min_airspeed_for_bearing, 30.f, 0.1f); + + // TEST DESCRIPTION: infeasible bearing, with |wind| = |airspeed|. Align with wind + + // GIVEN: bearing east + bearing = M_PI_F / 2.f; + airspeed_max = 25.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading sp due North with a min airspeed equal to airspeed_max + EXPECT_NEAR(heading_setpoint, 0.f, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, airspeed_max, 0.1f); + + // TEST DESCRIPTION: infeasible bearing, with |wind| > |airspeed|. Aircraft should have a heading between the target bearing + // and wind direction to minimize drift while still attempting to reach the bearing. + + // GIVEN: bearing NE + bearing = M_PI_F / 4.f; + airspeed_max = 20.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading setpoint to be between the target bearing and the cross wind + // & the minimum airspeed to be = maximum airspeed + EXPECT_TRUE((heading_setpoint > -M_PI_F / 2.f) && (heading_setpoint < bearing)); + EXPECT_NEAR(min_airspeed_for_bearing, airspeed_max, 0.1f); +} + +TEST(NpfgTest, ExcessTailWind) +{ + CourseToAirspeedRefMapper _course_to_airspeed; + + // GIVEN: bearing due East and wind from the West + const Vector2f wind_vel(0.f, 25.f); + float bearing = M_PI_2_F; + float airspeed_max = 25.f; + float min_ground_speed = 5.0f; + float airspeed_setpoint = 15.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + const float min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + float airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + float heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading due East with a min airspeed equal to 0 + EXPECT_NEAR(heading_setpoint, M_PI_2_F, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, 0.f, 0.1f); +} + +TEST(NpfgTest, ExcessCrossWind) +{ + // TEST DESCRIPTION: infeasible bearing, with |wind| > |airspeed|. Aircraft should have a heading between the target bearing + // and wind direction to minimize drift while still attempting to reach the bearing. + + CourseToAirspeedRefMapper _course_to_airspeed; + + // GIVEN: bearing due North, strong wind due East + const Vector2f wind_vel(0, 30.f); + float bearing = 0.f; + float airspeed_max = 25.f; + float min_ground_speed = 5.f; + float airspeed_setpoint = 15.f; + + // WHEN: we update bearing and airspeed magnitude augmentation + float min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + float airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + float heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + // THEN: expect heading setpoint to be between the target bearing and the cross wind + // & the minimum airspeed to be = maximum airspeed + EXPECT_TRUE((heading_setpoint > -M_PI_F / 2.f) && (heading_setpoint < bearing)); + EXPECT_NEAR(min_airspeed_for_bearing, airspeed_max, 0.1f); + + // TEST DESCRIPTION: infeasible bearing, with |wind| = |airspeed|. Align with wind. + + airspeed_max = 30.f; + + min_airspeed_for_bearing = _course_to_airspeed.getMinAirspeedForCurrentBearing(bearing, wind_vel, + airspeed_max, min_ground_speed); + + airspeed_setpoint_adapted = math::constrain(airspeed_setpoint, min_airspeed_for_bearing, airspeed_max); + + heading_setpoint = matrix::wrap_pi(_course_to_airspeed.mapCourseSetpointToHeadingSetpoint(bearing, wind_vel, + airspeed_setpoint_adapted)); + + EXPECT_NEAR(heading_setpoint, -M_PI_F / 2.f, 0.01f); + EXPECT_NEAR(min_airspeed_for_bearing, airspeed_max, 0.1f); +} + +TEST(NpfgTest, HeadingControl) +{ + AirspeedDirectionController _airspeed_reference_controller; + const float p_gain = 0.8885f; + + // GIVEN: that we are already aligned with out heading setpoint + float heading_sp = 0.f; + float heading = 0.f; + float airspeed = 15.f; + + // WHEN: we compute the lateral acceleration setpoint + float lateral_acceleration_setpoint = _airspeed_reference_controller.controlHeading(heading_sp, heading, airspeed); + + // THEN: we expect 0 lateral acceleration + EXPECT_NEAR(lateral_acceleration_setpoint, 0.f, 0.01f); + + // GIVEN: current heading 45 deg NW + heading = - M_PI_F / 4.f; + + // WHEN: we compute the lateral acceleration setpoint + lateral_acceleration_setpoint = _airspeed_reference_controller.controlHeading(heading_sp, heading, airspeed); + + // THEN: we expect a positive lateral acceleration input. = Airspeed vector + // required to correct the difference between the setpoint and the current heading, + // scaled by p_gain. + EXPECT_NEAR(lateral_acceleration_setpoint, airspeed * sinf(heading_sp - heading) * p_gain, 0.01f); + + // GIVEN: current heading 180 (South) + heading = M_PI_F; + + // WHEN: we compute the lateral acceleration setpoint + lateral_acceleration_setpoint = _airspeed_reference_controller.controlHeading(heading_sp, heading, airspeed); + + // THEN: we we expect maxmimum lateral acceleration setpoint + EXPECT_NEAR(lateral_acceleration_setpoint, airspeed * p_gain, 0.01f); +} From 83280dcfec1fc8e5e350c8d76ddaa8525ace8350 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 10 Apr 2025 11:28:37 +0200 Subject: [PATCH 037/130] TECS: protect against NAN in pitch integrator by limiting tas input to min tas Signed-off-by: Silvan Fuhrer --- src/lib/tecs/TECS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index e519246099..5ff73eb83c 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -469,7 +469,7 @@ void TECSControl::_calcPitchControlUpdate(float dt, const Input &input, const Co if (param.integrator_gain_pitch > FLT_EPSILON) { // Calculate derivative from change in climb angle to rate of change of specific energy balance - const float climb_angle_to_SEB_rate = input.tas * CONSTANTS_ONE_G; + const float climb_angle_to_SEB_rate = max(input.tas, param.tas_min) * CONSTANTS_ONE_G; // Calculate pitch integrator input term float pitch_integ_input = _getControlError(seb_rate) * param.integrator_gain_pitch / climb_angle_to_SEB_rate; From a849ab9de594b4d6a21e636aec2886866660ee10 Mon Sep 17 00:00:00 2001 From: Silvan Date: Sat, 5 Apr 2025 14:49:38 +0200 Subject: [PATCH 038/130] FW: Re-organize param sections for FW params Params that are used by FW Mode Manager - FW NPFG: NPFG params, should be renamed to FW Lateral Control once moved to the lat/lon controller - FW Auto Takeoff - FW Auto Landing Params used by Fw Lat/Long Controller: - FW Lateral Control - FW Longitudinal Control Params used by both: - FW General Params used by Performance model: - FW Performance (could be moerged with FW General?) Signed-off-by: Silvan --- .../fw_lat_long_params.c | 42 +++++++++---------- .../fw_path_navigation_params.c | 41 +++++++++--------- .../launchdetection/launchdetection_params.c | 6 +-- 3 files changed, 45 insertions(+), 44 deletions(-) diff --git a/src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c b/src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c index 130c0a1bd7..0856e8c123 100644 --- a/src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c +++ b/src/modules/fw_lateral_longitudinal_control/fw_lat_long_params.c @@ -8,7 +8,7 @@ * @min 0 * @decimal 0 * @increment 1 - * @group FW Path Control + * @group FW Lateral Control */ PARAM_DEFINE_FLOAT(FW_PN_R_SLEW_MAX, 90.0f); @@ -23,7 +23,7 @@ PARAM_DEFINE_FLOAT(FW_PN_R_SLEW_MAX, 90.0f); * @max 40 * @decimal 1 * @increment 0.5 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); @@ -41,7 +41,7 @@ PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); * @max 1.0 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); @@ -59,7 +59,7 @@ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); * @min -1 * @decimal 0 * @increment 1 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_THR_LOW_HGT, -1.f); @@ -72,7 +72,7 @@ PARAM_DEFINE_FLOAT(FW_T_THR_LOW_HGT, -1.f); * @max 1.0 * @decimal 3 * @increment 0.01 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_THR_DAMPING, 0.05f); @@ -86,7 +86,7 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMPING, 0.05f); * @max 1.0 * @decimal 3 * @increment 0.005 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_THR_INTEG, 0.02f); @@ -100,7 +100,7 @@ PARAM_DEFINE_FLOAT(FW_T_THR_INTEG, 0.02f); * @max 2.0 * @decimal 2 * @increment 0.05 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f); @@ -116,7 +116,7 @@ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f); * @max 10.0 * @decimal 1 * @increment 0.5 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); @@ -130,7 +130,7 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); * @max 10.0 * @decimal 2 * @increment 0.1 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.07f); @@ -144,7 +144,7 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.07f); * @max 10.0 * @decimal 2 * @increment 0.1 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_SPD_DEV_STD, 0.2f); @@ -159,7 +159,7 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_DEV_STD, 0.2f); * @max 10.0 * @decimal 2 * @increment 0.1 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_SPD_PRC_STD, 0.2f); @@ -174,7 +174,7 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_PRC_STD, 0.2f); * @max 20.0 * @decimal 1 * @increment 0.5 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); @@ -185,7 +185,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); * @max 2.0 * @decimal 2 * @increment 0.1 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f); @@ -195,7 +195,7 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f); * @min 2.0 * @decimal 2 * @increment 0.5 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f); @@ -207,7 +207,7 @@ PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f); * * @min -1.0 * @decimal 0 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_F_ALT_ERR, -1.0f); @@ -218,7 +218,7 @@ PARAM_DEFINE_FLOAT(FW_T_F_ALT_ERR, -1.0f); * @max 1.0 * @decimal 2 * @increment 0.05 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.3f); @@ -228,7 +228,7 @@ PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.3f); * @min 2.0 * @decimal 2 * @increment 0.5 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f); @@ -241,7 +241,7 @@ PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f); * @max 2 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_STE_R_TC, 0.4f); @@ -253,7 +253,7 @@ PARAM_DEFINE_FLOAT(FW_T_STE_R_TC, 0.4f); * @max 3 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f); @@ -267,7 +267,7 @@ PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f); * @min 0 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_WIND_ARSP_SC, 0.f); @@ -279,6 +279,6 @@ PARAM_DEFINE_FLOAT(FW_WIND_ARSP_SC, 0.f); * @max 15.0 * @decimal 1 * @increment 0.5 - * @group FW TECS + * @group FW Longitudinal Control */ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); diff --git a/src/modules/fw_pos_control/fw_path_navigation_params.c b/src/modules/fw_pos_control/fw_path_navigation_params.c index 9f82c22fb4..2269ba79f1 100644 --- a/src/modules/fw_pos_control/fw_path_navigation_params.c +++ b/src/modules/fw_pos_control/fw_path_navigation_params.c @@ -122,6 +122,7 @@ PARAM_DEFINE_FLOAT(NPFG_SW_DST_MLT, 0.32f); */ PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f); + /** * Minimum pitch angle setpoint * @@ -132,7 +133,7 @@ PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f); * @max 0.0 * @decimal 1 * @increment 0.5 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f); @@ -146,7 +147,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f); * @max 60.0 * @decimal 1 * @increment 0.5 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 30.0f); @@ -160,7 +161,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 30.0f); * @max 65.0 * @decimal 1 * @increment 0.5 - * @group FW Path Control + * @group FW General */ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f); @@ -175,7 +176,7 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f); * @max 1.0 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); @@ -191,7 +192,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); * @max 1.0 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); @@ -205,7 +206,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); * @max 0.4 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_THR_IDLE, 0.0f); @@ -232,7 +233,7 @@ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); * @max 30.0 * @decimal 1 * @increment 0.5 - * @group FW Path Control + * @group FW Auto Takeoff */ PARAM_DEFINE_FLOAT(FW_TKO_PITCH_MIN, 10.0f); @@ -247,7 +248,7 @@ PARAM_DEFINE_FLOAT(FW_TKO_PITCH_MIN, 10.0f); * @min -1.0 * @decimal 1 * @increment 0.1 - * @group FW TECS + * @group FW Auto Takeoff */ PARAM_DEFINE_FLOAT(FW_TKO_AIRSPD, -1.0f); @@ -365,7 +366,7 @@ PARAM_DEFINE_FLOAT(FW_LND_THRTC_SC, 1.0f); * @max 2.0 * @decimal 1 * @increment 1.0 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); @@ -378,7 +379,7 @@ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); * @max 3 * @bit 0 Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick) * @bit 1 Enable airspeed setpoint via sticks in altitude and position flight mode - * @group FW Path Control + * @group FW General */ PARAM_DEFINE_INT32(FW_POS_STK_CONF, 2); @@ -393,7 +394,7 @@ PARAM_DEFINE_INT32(FW_POS_STK_CONF, 2); * @max 15 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_T_CLMB_R_SP, 3.0f); @@ -408,7 +409,7 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_R_SP, 3.0f); * @max 15 * @decimal 2 * @increment 0.01 - * @group FW TECS + * @group FW General */ PARAM_DEFINE_FLOAT(FW_T_SINK_R_SP, 2.0f); @@ -422,7 +423,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_R_SP, 2.0f); * @unit s * @min 0 * @max 3600 - * @group Mission + * @group FW General */ PARAM_DEFINE_INT32(FW_GPSF_LT, 30); @@ -436,7 +437,7 @@ PARAM_DEFINE_INT32(FW_GPSF_LT, 30); * @max 30.0 * @decimal 1 * @increment 0.5 - * @group Mission + * @group FW General */ PARAM_DEFINE_FLOAT(FW_GPSF_R, 15.0f); @@ -450,7 +451,7 @@ PARAM_DEFINE_FLOAT(FW_GPSF_R, 15.0f); * @min 0.1 * @decimal 1 * @increment 0.1 - * @group FW Geometry + * @group FW General */ PARAM_DEFINE_FLOAT(FW_WING_SPAN, 3.0); @@ -464,7 +465,7 @@ PARAM_DEFINE_FLOAT(FW_WING_SPAN, 3.0); * @min 0.0 * @decimal 1 * @increment 1 - * @group FW Geometry + * @group FW General */ PARAM_DEFINE_FLOAT(FW_WING_HEIGHT, 0.5); @@ -578,7 +579,7 @@ PARAM_DEFINE_INT32(FW_LND_ABORT, 3); * Not compatible with runway takeoff. * * @boolean - * @group FW Launch detection + * @group FW Auto Takeoff */ PARAM_DEFINE_INT32(FW_LAUN_DETCN_ON, 0); @@ -593,7 +594,7 @@ PARAM_DEFINE_INT32(FW_LAUN_DETCN_ON, 0); * @max 1.0 * @decimal 2 * @increment 0.01 - * @group FW Rate Control + * @group FW Auto Takeoff */ PARAM_DEFINE_FLOAT(FW_FLAPS_TO_SCL, 0.0f); @@ -608,7 +609,7 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_TO_SCL, 0.0f); * @max 1.0 * @decimal 2 * @increment 0.01 - * @group FW Rate Control + * @group FW Auto Landing */ PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f); @@ -620,6 +621,6 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f); * @max 1.0 * @decimal 2 * @increment 0.01 - * @group FW Attitude Control + * @group FW Auto Landing */ PARAM_DEFINE_FLOAT(FW_SPOILERS_LND, 0.f); diff --git a/src/modules/fw_pos_control/launchdetection/launchdetection_params.c b/src/modules/fw_pos_control/launchdetection/launchdetection_params.c index 63e14bedbd..eee3d7ccef 100644 --- a/src/modules/fw_pos_control/launchdetection/launchdetection_params.c +++ b/src/modules/fw_pos_control/launchdetection/launchdetection_params.c @@ -48,7 +48,7 @@ * @min 0 * @decimal 1 * @increment 0.5 - * @group FW Launch detection + * @group FW Auto Takeoff */ PARAM_DEFINE_FLOAT(FW_LAUN_AC_THLD, 30.0f); @@ -62,7 +62,7 @@ PARAM_DEFINE_FLOAT(FW_LAUN_AC_THLD, 30.0f); * @max 5.0 * @decimal 2 * @increment 0.05 - * @group FW Launch detection + * @group FW Auto Takeoff */ PARAM_DEFINE_FLOAT(FW_LAUN_AC_T, 0.05f); @@ -76,6 +76,6 @@ PARAM_DEFINE_FLOAT(FW_LAUN_AC_T, 0.05f); * @max 10.0 * @decimal 1 * @increment 0.5 - * @group FW Launch detection + * @group FW Auto Takeoff */ PARAM_DEFINE_FLOAT(FW_LAUN_MOT_DEL, 0.0f); From 26009461728de880923f803d087404d4a326f271 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 11 Apr 2025 17:08:28 +0200 Subject: [PATCH 039/130] FW Attitude Controller: Wheel controller rework add RunwayControl messge to pass wheel steering controls to wheel controller Signed-off-by: Silvan Fuhrer Runway takeoff: specify that RWTO_TKOFF is directly applied during takeoff Signed-off-by: Silvan Fuhrer msg/RateCtrlStatus: remove unused wheel_rate_integ field The wheel rate controller is not run in the moduels that are now running the MC/FW rate controllers, so thsi field canot be filled. Signed-off-by: Silvan Fuhrer wheel rate controller: use speed scaler quadratically on integrator Signed-off-by: Silvan Fuhrer wheel yaw controller: use a time constant of 0.1 Signed-off-by: Silvan Fuhrer FW Attitude Controller: lock heading setpoint for wheels to initial heading Signed-off-by: Silvan Fuhrer --- msg/CMakeLists.txt | 1 + msg/FixedWingRunwayControl.msg | 8 ++ msg/RateCtrlStatus.msg | 1 - .../FixedwingAttitudeControl.cpp | 106 ++++++++---------- .../FixedwingAttitudeControl.hpp | 3 + .../fw_att_control/fw_wheel_controller.cpp | 4 +- .../FixedwingPositionControl.cpp | 32 ++++-- .../FixedwingPositionControl.hpp | 2 + .../runway_takeoff/runway_takeoff_params.c | 2 +- src/modules/logger/logged_topics.cpp | 1 + 10 files changed, 89 insertions(+), 71 deletions(-) create mode 100644 msg/FixedWingRunwayControl.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index e3008ae917..29af39b27f 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -94,6 +94,7 @@ set(msg_files FixedWingLongitudinalSetpoint.msg FixedWingLateralGuidanceStatus.msg FixedWingLateralStatus.msg + FixedWingRunwayControl.msg GeneratorStatus.msg GeofenceResult.msg GeofenceStatus.msg diff --git a/msg/FixedWingRunwayControl.msg b/msg/FixedWingRunwayControl.msg new file mode 100644 index 0000000000..a74d702c10 --- /dev/null +++ b/msg/FixedWingRunwayControl.msg @@ -0,0 +1,8 @@ +# Auxiliary control fields for fixed-wing runway takeoff/landing + +# Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +uint64 timestamp # [us] time since system start + +bool wheel_steering_enabled # Flag that enables the wheel steering. +float32 wheel_steering_nudging_rate # [norm] [-1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. diff --git a/msg/RateCtrlStatus.msg b/msg/RateCtrlStatus.msg index 3f5644699d..b1e4d4feb1 100644 --- a/msg/RateCtrlStatus.msg +++ b/msg/RateCtrlStatus.msg @@ -4,4 +4,3 @@ uint64 timestamp # time since system start (microseconds) float32 rollspeed_integ float32 pitchspeed_integ float32 yawspeed_integ -float32 wheel_rate_integ # FW only and optional diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp index c9a6d921fc..f9328635e6 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp @@ -47,6 +47,7 @@ FixedwingAttitudeControl::FixedwingAttitudeControl(bool vtol) : { /* fetch initial parameter values */ parameters_update(); + _landing_gear_wheel_pub.advertise(); } FixedwingAttitudeControl::~FixedwingAttitudeControl() @@ -82,6 +83,7 @@ FixedwingAttitudeControl::parameters_update() _wheel_ctrl.set_k_ff(_param_fw_wr_ff.get()); _wheel_ctrl.set_integrator_max(_param_fw_wr_imax.get()); _wheel_ctrl.set_max_rate(radians(_param_fw_w_rmax.get())); + _wheel_ctrl.set_time_constant(0.1f); } void @@ -267,13 +269,6 @@ void FixedwingAttitudeControl::Run() vehicle_land_detected_poll(); - bool wheel_control = false; - - // TODO listen to a runway_takeoff_status to determine when to control wheel - if (_param_fw_w_en.get() && _vcontrol_mode.flag_control_auto_enabled) { - wheel_control = true; - } - /* if we are in rotary wing mode, do nothing */ if (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !_vehicle_status.is_vtol) { perf_end(_loop_perf); @@ -295,27 +290,6 @@ void FixedwingAttitudeControl::Run() _rates_sp.reset_integral = false; } - float groundspeed_scale = 1.f; - - if (wheel_control) { - if (_local_pos_sub.updated()) { - vehicle_local_position_s vehicle_local_position; - - if (_local_pos_sub.copy(&vehicle_local_position)) { - _groundspeed = sqrtf(vehicle_local_position.vx * vehicle_local_position.vx + vehicle_local_position.vy * - vehicle_local_position.vy); - } - } - - // Use stall airspeed to calculate ground speed scaling region. Don't scale below gspd_scaling_trim - float gspd_scaling_trim = (_param_fw_airspd_stall.get()); - - if (_groundspeed > gspd_scaling_trim) { - groundspeed_scale = gspd_scaling_trim / _groundspeed; - - } - } - /* Run attitude controllers */ if (_vcontrol_mode.flag_control_attitude_enabled && _in_fw_or_transition_wo_tailsitter_transition) { @@ -333,13 +307,6 @@ void FixedwingAttitudeControl::Run() _yaw_ctrl.control_yaw(roll_sp, _pitch_ctrl.get_euler_rate_setpoint(), euler_angles.phi(), euler_angles.theta(), get_airspeed_constrained()); - if (wheel_control) { - _wheel_ctrl.control_attitude(euler_sp.psi(), euler_angles.psi()); - - } else { - _wheel_ctrl.reset_integrator(); - } - /* Update input data for rate controllers */ Vector3f body_rates_setpoint = Vector3f(_roll_ctrl.get_body_rate_setpoint(), _pitch_ctrl.get_body_rate_setpoint(), _yaw_ctrl.get_body_rate_setpoint()); @@ -380,40 +347,61 @@ void FixedwingAttitudeControl::Run() _rate_sp_pub.publish(_rates_sp); } } + } - // wheel control - float wheel_u = 0.f; + // steering wheel control + fixed_wing_runway_control_s runway_control{}; + _fixed_wing_runway_control_sub.copy(&runway_control); + const bool runway_control_recent = hrt_elapsed_time(&runway_control.timestamp) < 1_s; + const bool wheel_controller_enabled = _param_fw_w_en.get() && _vcontrol_mode.flag_control_auto_enabled + && runway_control_recent && runway_control.wheel_steering_enabled; - if (_vcontrol_mode.flag_control_manual_enabled) { - // always direct control of steering wheel with yaw stick in manual modes - wheel_u = _manual_control_setpoint.yaw; + float groundspeed_scale = 1.f; + float wheel_u = 0.f; - } else { - vehicle_angular_velocity_s angular_velocity{}; - _vehicle_rates_sub.copy(&angular_velocity); + if (wheel_controller_enabled) { + if (_local_pos_sub.updated()) { + vehicle_local_position_s vehicle_local_position; - // XXX: yaw_sp_move_rate here is an abuse -- used to ferry manual yaw inputs from - // position controller during auto modes _manual_control_setpoint.r gets passed - // whenever nudging is enabled, otherwise zero - const float wheel_controller_output = _wheel_ctrl.control_bodyrate(dt, angular_velocity.xyz[2], _groundspeed, - groundspeed_scale); - wheel_u = wheel_control ? wheel_controller_output + _att_sp.yaw_sp_move_rate : 0.f; + if (_local_pos_sub.copy(&vehicle_local_position)) { + _groundspeed = sqrtf(vehicle_local_position.vx * vehicle_local_position.vx + vehicle_local_position.vy * + vehicle_local_position.vy); + } } - _landing_gear_wheel.normalized_wheel_setpoint = PX4_ISFINITE(wheel_u) ? wheel_u : 0.f; - _landing_gear_wheel.timestamp = hrt_absolute_time(); - _landing_gear_wheel_pub.publish(_landing_gear_wheel); + // Use stall airspeed to calculate ground speed scaling region. Don't scale below gspd_scaling_trim + float gspd_scaling_trim = (_param_fw_airspd_stall.get()); + + if (_groundspeed > gspd_scaling_trim) { + groundspeed_scale = gspd_scaling_trim / _groundspeed; + + } + + // set now yaw setpoint once we're entering the first time + if (!PX4_ISFINITE(_steering_wheel_yaw_setpoint)) { + _steering_wheel_yaw_setpoint = euler_angles.psi(); + } + + _wheel_ctrl.control_attitude(_steering_wheel_yaw_setpoint, euler_angles.psi()); + + vehicle_angular_velocity_s angular_velocity{}; + _vehicle_rates_sub.copy(&angular_velocity); + + const float wheel_controller_output = wheel_controller_enabled ? _wheel_ctrl.control_bodyrate(dt, + angular_velocity.xyz[2], _groundspeed, + groundspeed_scale) : 0.f; + + wheel_u = wheel_controller_output + runway_control.wheel_steering_nudging_rate; } else { - // full manual _wheel_ctrl.reset_integrator(); - - _landing_gear_wheel.normalized_wheel_setpoint = PX4_ISFINITE(_manual_control_setpoint.yaw) ? - _manual_control_setpoint.yaw : 0.f; - _landing_gear_wheel.timestamp = hrt_absolute_time(); - _landing_gear_wheel_pub.publish(_landing_gear_wheel); - + _steering_wheel_yaw_setpoint = NAN; + wheel_u = _manual_control_setpoint.yaw; // direct yaw stick to wheel steering } + + _landing_gear_wheel.normalized_wheel_setpoint = PX4_ISFINITE(wheel_u) ? wheel_u : 0.f; + _landing_gear_wheel.timestamp = hrt_absolute_time(); + _landing_gear_wheel_pub.publish(_landing_gear_wheel); } // backup schedule diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp index 43432a4a3a..73a08c00e0 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp @@ -54,6 +54,7 @@ #include #include #include +#include #include #include #include @@ -100,6 +101,7 @@ private: uORB::Subscription _att_sp_sub{ORB_ID(vehicle_attitude_setpoint)}; /**< vehicle attitude setpoint */ uORB::Subscription _autotune_attitude_control_status_sub{ORB_ID(autotune_attitude_control_status)}; + uORB::Subscription _fixed_wing_runway_control_sub{ORB_ID(fixed_wing_runway_control)}; uORB::Subscription _local_pos_sub{ORB_ID(vehicle_local_position)}; /**< local position subscription */ uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; /**< notification of manual control updates */ uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; /**< vehicle status subscription */ @@ -129,6 +131,7 @@ private: bool _landed{true}; float _groundspeed{0.f}; bool _in_fw_or_transition_wo_tailsitter_transition{false}; // only run the FW attitude controller in these states + float _steering_wheel_yaw_setpoint{NAN}; DEFINE_PARAMETERS( (ParamFloat) _param_fw_airspd_max, diff --git a/src/modules/fw_att_control/fw_wheel_controller.cpp b/src/modules/fw_att_control/fw_wheel_controller.cpp index e26d9a5d38..3868a97369 100644 --- a/src/modules/fw_att_control/fw_wheel_controller.cpp +++ b/src/modules/fw_att_control/fw_wheel_controller.cpp @@ -58,7 +58,7 @@ float WheelController::control_bodyrate(float dt, float body_z_rate, float groun if (_k_i > 0.f && groundspeed > 1.f) { // only start integrating when above 1m/s - float id = rate_error * dt * groundspeed_scaler; + float id = rate_error * dt * groundspeed_scaler * groundspeed_scaler; if (_last_output < -1.f) { /* only allow motion to center: increase value */ @@ -74,7 +74,7 @@ float WheelController::control_bodyrate(float dt, float body_z_rate, float groun /* Apply PI rate controller and store non-limited output */ _last_output = _body_rate_setpoint * _k_ff * groundspeed_scaler + - groundspeed_scaler * groundspeed_scaler * (rate_error * _k_p + _integrator); + groundspeed_scaler * groundspeed_scaler * (rate_error * _k_p) + _integrator; return math::constrain(_last_output, -1.f, 1.f); } diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 672a718dc8..fc19682529 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -71,6 +71,7 @@ FixedwingPositionControl::FixedwingPositionControl() : _flaps_setpoint_pub.advertise(); _spoilers_setpoint_pub.advertise(); _fixed_wing_lateral_guidance_status_pub.advertise(); + _fixed_wing_runway_control_pub.advertise(); parameters_update(); } @@ -1094,11 +1095,6 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _runway_takeoff.update(now, takeoff_airspeed, _airspeed_eas, _current_altitude - _takeoff_ground_alt, clearance_altitude_amsl - _takeoff_ground_alt); - // XXX: hacky way to pass through manual nose-wheel incrementing. need to clean this interface. - if (_param_rwto_nudge.get()) { - _att_sp.yaw_sp_move_rate = _manual_control_setpoint.yaw; - } - const Vector2f start_pos_local = _global_local_proj_ref.project(_takeoff_init_position(0), _takeoff_init_position(1)); const Vector2f takeoff_waypoint_local = _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon); @@ -1154,6 +1150,13 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo _new_landing_gear_position = landing_gear_s::GEAR_UP; } + fixed_wing_runway_control_s fw_runway_control{}; + fw_runway_control.timestamp = now; + fw_runway_control.wheel_steering_enabled = true; + fw_runway_control.wheel_steering_nudging_rate = _param_rwto_nudge.get() ? _manual_control_setpoint.yaw : 0.f; + + _fixed_wing_runway_control_pub.publish(fw_runway_control); + } else { /* Perform launch detection */ if (!_skipping_takeoff_detection && _param_fw_laun_detcn_on.get() && @@ -1440,6 +1443,14 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, _ctrl_configuration_handler.setSinkRateTarget(desired_max_sinkrate); } + fixed_wing_runway_control_s fw_runway_control{}; + fw_runway_control.timestamp = now; + fw_runway_control.wheel_steering_enabled = true; + fw_runway_control.wheel_steering_nudging_rate = _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled ? + _manual_control_setpoint.yaw : 0.f; + + _fixed_wing_runway_control_pub.publish(fw_runway_control); + _flaps_setpoint = _param_fw_flaps_lnd_scl.get(); _spoilers_setpoint = _param_fw_spoilers_lnd.get(); @@ -1595,6 +1606,14 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, _ctrl_configuration_handler.setSinkRateTarget(desired_max_sinkrate); } + fixed_wing_runway_control_s fw_runway_control{}; + fw_runway_control.timestamp = now; + fw_runway_control.wheel_steering_enabled = true; + fw_runway_control.wheel_steering_nudging_rate = _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled ? + _manual_control_setpoint.yaw : 0.f; + + _fixed_wing_runway_control_pub.publish(fw_runway_control); + _ctrl_configuration_handler.setLateralAccelMax(rollAngleToLateralAccel(getMaxRollAngleNearGround(_current_altitude, terrain_alt))); @@ -2002,9 +2021,6 @@ FixedwingPositionControl::Run() // by default set speed weight to the param value, can be overwritten inside the methods below _ctrl_configuration_handler.setSpeedWeight(_param_t_spdweight.get()); - // default to zero - is used (IN A HACKY WAY) to pass direct nose wheel steering via yaw stick to the actuators during auto takeoff - _att_sp.yaw_sp_move_rate = 0.0f; - if (_control_mode_current != FW_POSCTRL_MODE_AUTO_LANDING_STRAIGHT && _control_mode_current != FW_POSCTRL_MODE_AUTO_LANDING_CIRCULAR) { reset_landing_state(); diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_pos_control/FixedwingPositionControl.hpp index aea0dd5a89..33a0cd87e7 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.hpp @@ -68,6 +68,7 @@ #include #include #include +#include #include #include #include @@ -198,6 +199,7 @@ private: uORB::PublicationData _lateral_ctrl_sp_pub{ORB_ID(fixed_wing_lateral_setpoint)}; uORB::PublicationData _longitudinal_ctrl_sp_pub{ORB_ID(fixed_wing_longitudinal_setpoint)}; uORB::Publication _fixed_wing_lateral_guidance_status_pub{ORB_ID(fixed_wing_lateral_guidance_status)}; + uORB::Publication _fixed_wing_runway_control_pub{ORB_ID(fixed_wing_runway_control)}; manual_control_setpoint_s _manual_control_setpoint{}; position_setpoint_triplet_s _pos_sp_triplet{}; diff --git a/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c b/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c index e33fa9d616..68afdeffa1 100644 --- a/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c +++ b/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c @@ -48,7 +48,7 @@ PARAM_DEFINE_INT32(RWTO_TKOFF, 0); /** - * Max throttle during runway takeoff. + * Throttle during runway takeoff. * * @unit norm * @min 0.0 diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 691c57adb4..3d011cbc5c 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -154,6 +154,7 @@ void LoggedTopics::add_default_topics() add_topic("lateral_control_configuration"); add_optional_topic("fixed_wing_lateral_guidance_status", 100); add_optional_topic("fixed_wing_lateral_status", 100); + add_optional_topic("fixed_wing_runway_control", 100); // multi topics add_optional_topic_multi("actuator_outputs", 100, 3); From 259e7d1d5373dbad1ee27b1d72d1ae66394c4ea3 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 11 Apr 2025 18:07:27 +0200 Subject: [PATCH 040/130] FWModeManger: remove throttle spike during flaring by waiting with height rate change Signed-off-by: Silvan Fuhrer --- .../fw_pos_control/FixedwingPositionControl.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index fc19682529..eb9472eae4 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1356,8 +1356,14 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, const float flare_ramp_interpolator_sqrt = sqrtf(flare_ramp_interpolator); - const float height_rate_setpoint = flare_ramp_interpolator_sqrt * (-_param_fw_lnd_fl_sink.get()) + - (1.0f - flare_ramp_interpolator_sqrt) * _flare_states.initial_height_rate_setpoint; + // Use separate ramp for the altitude setpoint that's starting only when the other is finished + // to allow motor to be ramped down before height rate setpoint is adapted for flaring. + const float flare_hieght_rate_interpolator = math::constrain((seconds_since_flare_start - + _param_fw_lnd_fl_time.get()) / (_param_fw_lnd_fl_time.get()), 0.f, 1.f); + const float flare_hieght_rate_interpolator_sqrt = sqrt(flare_hieght_rate_interpolator); + + const float height_rate_setpoint = flare_hieght_rate_interpolator_sqrt * (-_param_fw_lnd_fl_sink.get()) + + (1.0f - flare_hieght_rate_interpolator_sqrt) * _flare_states.initial_height_rate_setpoint; float pitch_min_rad = flare_ramp_interpolator_sqrt * radians(_param_fw_lnd_fl_pmin.get()) + (1.0f - flare_ramp_interpolator_sqrt) * radians(_param_fw_p_lim_min.get()); From 8c1f7ec7c0cd40b35c1d117974867cde6e2bc156 Mon Sep 17 00:00:00 2001 From: Silvan Date: Sat, 5 Apr 2025 14:09:51 +0200 Subject: [PATCH 041/130] rename FWPositionController to FWModeManager Signed-off-by: Silvan --- ROMFS/px4fmu_common/init.d/rc.fw_apps | 2 +- ROMFS/px4fmu_common/init.d/rc.vtol_apps | 2 +- .../ctrl-zero-h7-oem-revg/default.px4board | 2 +- boards/airmind/mindpx-v2/default.px4board | 2 +- boards/ark/fmu-v6x/default.px4board | 2 +- boards/ark/fpv/default.px4board | 2 +- boards/auterion/fmu-v6s/default.px4board | 3 +- boards/auterion/fmu-v6s/multicopter.px4board | 3 +- boards/auterion/fmu-v6s/rover.px4board | 3 +- boards/av/x-v1/default.px4board | 2 +- boards/beaglebone/blue/default.px4board | 2 +- .../bluerobotics/navigator/default.px4board | 3 +- boards/corvon/743v1/default.px4board | 3 +- boards/cuav/7-nano/default.px4board | 2 +- boards/cuav/nora/default.px4board | 2 +- boards/cuav/x7pro/default.px4board | 2 +- boards/cubepilot/cubeorange/default.px4board | 2 +- .../cubepilot/cubeorangeplus/default.px4board | 2 +- boards/cubepilot/cubeyellow/default.px4board | 2 +- boards/emlid/navio2/default.px4board | 2 +- boards/hkust/nxt-dual/default.px4board | 2 +- boards/hkust/nxt-v1/default.px4board | 2 +- boards/holybro/durandal-v1/default.px4board | 2 +- boards/holybro/kakuteh7-wing/default.px4board | 3 +- boards/holybro/kakuteh7/default.px4board | 2 +- .../holybro/kakuteh7dualimu/default.px4board | 3 +- boards/holybro/kakuteh7mini/default.px4board | 2 +- boards/holybro/kakuteh7v2/default.px4board | 2 +- boards/holybro/pix32v5/default.px4board | 2 +- boards/matek/h743-mini/default.px4board | 2 +- boards/matek/h743-slim/default.px4board | 2 +- boards/matek/h743/default.px4board | 2 +- boards/micoair/h743-aio/default.px4board | 2 +- boards/micoair/h743-v2/default.px4board | 2 +- boards/micoair/h743/default.px4board | 2 +- boards/modalai/fc-v1/default.px4board | 2 +- boards/modalai/fc-v2/default.px4board | 2 +- boards/mro/ctrl-zero-classic/default.px4board | 2 +- boards/mro/ctrl-zero-f7-oem/default.px4board | 2 +- boards/mro/ctrl-zero-f7/default.px4board | 2 +- boards/mro/ctrl-zero-h7-oem/default.px4board | 2 +- boards/mro/ctrl-zero-h7/default.px4board | 2 +- boards/mro/pixracerpro/default.px4board | 2 +- boards/mro/x21-777/default.px4board | 2 +- boards/mro/x21/default.px4board | 2 +- boards/nxp/fmuk66-e/default.px4board | 2 +- boards/nxp/fmuk66-v3/default.px4board | 2 +- boards/nxp/mr-canhubk3/fmu.px4board | 2 +- boards/nxp/mr-canhubk3/sysview.px4board | 2 +- boards/nxp/mr-canhubk3/zenoh.px4board | 2 +- boards/nxp/tropic-community/default.px4board | 2 +- boards/px4/fmu-v2/fixedwing.px4board | 2 +- boards/px4/fmu-v3/default.px4board | 2 +- boards/px4/fmu-v4/default.px4board | 2 +- boards/px4/fmu-v4pro/default.px4board | 2 +- boards/px4/fmu-v5/default.px4board | 2 +- boards/px4/fmu-v5/protected.px4board | 2 +- boards/px4/fmu-v5/rover.px4board | 2 +- boards/px4/fmu-v5/stackcheck.px4board | 2 +- boards/px4/fmu-v5x/default.px4board | 2 +- boards/px4/fmu-v5x/rover.px4board | 2 +- boards/px4/fmu-v6c/default.px4board | 2 +- boards/px4/fmu-v6c/rover.px4board | 2 +- boards/px4/fmu-v6u/default.px4board | 2 +- boards/px4/fmu-v6u/rover.px4board | 2 +- boards/px4/fmu-v6x/default.px4board | 2 +- boards/px4/fmu-v6x/multicopter.px4board | 2 +- boards/px4/fmu-v6x/rover.px4board | 2 +- boards/px4/fmu-v6xrt/default.px4board | 2 +- boards/px4/fmu-v6xrt/rover.px4board | 2 +- boards/px4/raspberrypi/default.px4board | 2 +- boards/px4/sitl/default.px4board | 2 +- boards/px4/sitl/spacecraft.px4board | 2 +- boards/scumaker/pilotpi/default.px4board | 2 +- boards/siyi/n7/default.px4board | 2 +- .../smartap-airlink/default.px4board | 2 +- boards/thepeach/k1/default.px4board | 2 +- boards/thepeach/r1/default.px4board | 2 +- boards/x-mav/ap-h743v2/default.px4board | 2 +- boards/zeroone/x6/default.px4board | 2 +- posix-configs/SITL/init/test/test_shutdown | 6 +- posix-configs/bbblue/px4_fw.config | 2 +- posix-configs/rpi/pilotpi_fw.config | 3 +- posix-configs/rpi/px4_fw.config | 2 +- .../CMakeLists.txt | 10 +- .../ControllerConfigurationHandler.cpp | 0 .../ControllerConfigurationHandler.hpp | 0 .../FixedWingModeManager.cpp} | 138 +++++++++--------- .../FixedWingModeManager.hpp} | 16 +- src/modules/fw_mode_manager/Kconfig | 20 +++ .../figure_eight/CMakeLists.txt | 0 .../figure_eight/FigureEight.cpp | 0 .../figure_eight/FigureEight.hpp | 0 .../fw_mode_manager_params.c} | 0 .../launchdetection/CMakeLists.txt | 0 .../launchdetection/LaunchDetector.cpp | 0 .../launchdetection/LaunchDetector.h | 0 .../launchdetection/launchdetection_params.c | 0 .../runway_takeoff/CMakeLists.txt | 0 .../runway_takeoff/RunwayTakeoff.cpp | 0 .../runway_takeoff/RunwayTakeoff.h | 0 .../runway_takeoff/runway_takeoff_params.c | 0 src/modules/fw_pos_control/Kconfig | 20 --- 103 files changed, 197 insertions(+), 187 deletions(-) rename src/modules/{fw_pos_control => fw_mode_manager}/CMakeLists.txt (92%) rename src/modules/{fw_pos_control => fw_mode_manager}/ControllerConfigurationHandler.cpp (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/ControllerConfigurationHandler.hpp (100%) rename src/modules/{fw_pos_control/FixedwingPositionControl.cpp => fw_mode_manager/FixedWingModeManager.cpp} (94%) rename src/modules/{fw_pos_control/FixedwingPositionControl.hpp => fw_mode_manager/FixedWingModeManager.hpp} (98%) create mode 100644 src/modules/fw_mode_manager/Kconfig rename src/modules/{fw_pos_control => fw_mode_manager}/figure_eight/CMakeLists.txt (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/figure_eight/FigureEight.cpp (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/figure_eight/FigureEight.hpp (100%) rename src/modules/{fw_pos_control/fw_path_navigation_params.c => fw_mode_manager/fw_mode_manager_params.c} (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/launchdetection/CMakeLists.txt (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/launchdetection/LaunchDetector.cpp (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/launchdetection/LaunchDetector.h (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/launchdetection/launchdetection_params.c (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/runway_takeoff/CMakeLists.txt (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/runway_takeoff/RunwayTakeoff.cpp (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/runway_takeoff/RunwayTakeoff.h (100%) rename src/modules/{fw_pos_control => fw_mode_manager}/runway_takeoff/runway_takeoff_params.c (100%) delete mode 100644 src/modules/fw_pos_control/Kconfig diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps index b6f05837be..7597c989b3 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_apps +++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps @@ -15,7 +15,7 @@ control_allocator start # fw_rate_control start fw_att_control start -fw_pos_control start +fw_mode_manager start fw_lat_lon_control start airspeed_selector start diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_apps b/ROMFS/px4fmu_common/init.d/rc.vtol_apps index 9962f3c83a..16fb6ee5d6 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_apps +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_apps @@ -27,7 +27,7 @@ fi fw_rate_control start vtol fw_att_control start vtol -fw_pos_control start +fw_mode_manager start fw_lat_lon_control start vtol fw_autotune_attitude_control start vtol diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board index 844782f2af..326bb98a93 100644 --- a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board +++ b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board @@ -41,7 +41,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board index e34edeb0b7..67c4a57dd4 100644 --- a/boards/airmind/mindpx-v2/default.px4board +++ b/boards/airmind/mindpx-v2/default.px4board @@ -46,7 +46,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 6b767e4675..64b2ff9838 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -56,7 +56,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/ark/fpv/default.px4board b/boards/ark/fpv/default.px4board index ef0766f144..79f3ab19da 100644 --- a/boards/ark/fpv/default.px4board +++ b/boards/ark/fpv/default.px4board @@ -37,7 +37,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/auterion/fmu-v6s/default.px4board b/boards/auterion/fmu-v6s/default.px4board index bb1bd7fdc0..d99a2ae6a1 100644 --- a/boards/auterion/fmu-v6s/default.px4board +++ b/boards/auterion/fmu-v6s/default.px4board @@ -37,7 +37,8 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_FIGURE_OF_EIGHT=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/auterion/fmu-v6s/multicopter.px4board b/boards/auterion/fmu-v6s/multicopter.px4board index 296a35c21f..69617bda0c 100644 --- a/boards/auterion/fmu-v6s/multicopter.px4board +++ b/boards/auterion/fmu-v6s/multicopter.px4board @@ -3,7 +3,8 @@ CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=n CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_COMMON_RC=y diff --git a/boards/auterion/fmu-v6s/rover.px4board b/boards/auterion/fmu-v6s/rover.px4board index f754c54e36..2709b271b6 100644 --- a/boards/auterion/fmu-v6s/rover.px4board +++ b/boards/auterion/fmu-v6s/rover.px4board @@ -2,7 +2,8 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MC_ATT_CONTROL=n diff --git a/boards/av/x-v1/default.px4board b/boards/av/x-v1/default.px4board index a493a5623c..1ad68a8f71 100644 --- a/boards/av/x-v1/default.px4board +++ b/boards/av/x-v1/default.px4board @@ -42,7 +42,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/beaglebone/blue/default.px4board b/boards/beaglebone/blue/default.px4board index 5a2f5682aa..1e7db4fae5 100644 --- a/boards/beaglebone/blue/default.px4board +++ b/boards/beaglebone/blue/default.px4board @@ -30,7 +30,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/bluerobotics/navigator/default.px4board b/boards/bluerobotics/navigator/default.px4board index 49ff0a2aba..8812f00366 100644 --- a/boards/bluerobotics/navigator/default.px4board +++ b/boards/bluerobotics/navigator/default.px4board @@ -49,7 +49,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y CONFIG_MODULES_UUV_POS_CONTROL=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MC_ATT_CONTROL=y diff --git a/boards/corvon/743v1/default.px4board b/boards/corvon/743v1/default.px4board index 149bcaff21..ac84a53cd6 100644 --- a/boards/corvon/743v1/default.px4board +++ b/boards/corvon/743v1/default.px4board @@ -38,7 +38,8 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y diff --git a/boards/cuav/7-nano/default.px4board b/boards/cuav/7-nano/default.px4board index fc50c0ba7a..eb1dc29bc3 100644 --- a/boards/cuav/7-nano/default.px4board +++ b/boards/cuav/7-nano/default.px4board @@ -42,7 +42,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index b06d1005b3..b0db9a1735 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -50,7 +50,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index 5491c10fc1..eafa964372 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -50,7 +50,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/cubepilot/cubeorange/default.px4board b/boards/cubepilot/cubeorange/default.px4board index 411407613a..f10622bb3f 100644 --- a/boards/cubepilot/cubeorange/default.px4board +++ b/boards/cubepilot/cubeorange/default.px4board @@ -49,7 +49,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/cubepilot/cubeorangeplus/default.px4board b/boards/cubepilot/cubeorangeplus/default.px4board index 416ccf5483..8b2c0839b9 100644 --- a/boards/cubepilot/cubeorangeplus/default.px4board +++ b/boards/cubepilot/cubeorangeplus/default.px4board @@ -50,7 +50,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/cubepilot/cubeyellow/default.px4board b/boards/cubepilot/cubeyellow/default.px4board index 3717771be6..8d0dc3eee3 100644 --- a/boards/cubepilot/cubeyellow/default.px4board +++ b/boards/cubepilot/cubeyellow/default.px4board @@ -46,7 +46,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/emlid/navio2/default.px4board b/boards/emlid/navio2/default.px4board index 11a066013a..6498bf7820 100644 --- a/boards/emlid/navio2/default.px4board +++ b/boards/emlid/navio2/default.px4board @@ -32,7 +32,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/hkust/nxt-dual/default.px4board b/boards/hkust/nxt-dual/default.px4board index 18a7d92520..97b19358e5 100644 --- a/boards/hkust/nxt-dual/default.px4board +++ b/boards/hkust/nxt-dual/default.px4board @@ -39,7 +39,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board index 914bfd3b3a..0690280eea 100644 --- a/boards/hkust/nxt-v1/default.px4board +++ b/boards/hkust/nxt-v1/default.px4board @@ -41,7 +41,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/holybro/durandal-v1/default.px4board b/boards/holybro/durandal-v1/default.px4board index 199bc05367..627917d186 100644 --- a/boards/holybro/durandal-v1/default.px4board +++ b/boards/holybro/durandal-v1/default.px4board @@ -44,7 +44,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/holybro/kakuteh7-wing/default.px4board b/boards/holybro/kakuteh7-wing/default.px4board index f8440af002..08670e4781 100644 --- a/boards/holybro/kakuteh7-wing/default.px4board +++ b/boards/holybro/kakuteh7-wing/default.px4board @@ -37,7 +37,8 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/holybro/kakuteh7/default.px4board b/boards/holybro/kakuteh7/default.px4board index cdebf407b2..fed11068e6 100644 --- a/boards/holybro/kakuteh7/default.px4board +++ b/boards/holybro/kakuteh7/default.px4board @@ -45,7 +45,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/holybro/kakuteh7dualimu/default.px4board b/boards/holybro/kakuteh7dualimu/default.px4board index fbecd9f5af..5b4f4710a4 100644 --- a/boards/holybro/kakuteh7dualimu/default.px4board +++ b/boards/holybro/kakuteh7dualimu/default.px4board @@ -48,7 +48,8 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/holybro/kakuteh7mini/default.px4board b/boards/holybro/kakuteh7mini/default.px4board index b8ca1495a2..06bc5ffe7e 100644 --- a/boards/holybro/kakuteh7mini/default.px4board +++ b/boards/holybro/kakuteh7mini/default.px4board @@ -45,7 +45,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/holybro/kakuteh7v2/default.px4board b/boards/holybro/kakuteh7v2/default.px4board index 8bbb8f6a7e..8821361a69 100644 --- a/boards/holybro/kakuteh7v2/default.px4board +++ b/boards/holybro/kakuteh7v2/default.px4board @@ -45,7 +45,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/holybro/pix32v5/default.px4board b/boards/holybro/pix32v5/default.px4board index 94b177fb87..01c28a922c 100644 --- a/boards/holybro/pix32v5/default.px4board +++ b/boards/holybro/pix32v5/default.px4board @@ -50,7 +50,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/matek/h743-mini/default.px4board b/boards/matek/h743-mini/default.px4board index 26238797e0..965fec5459 100644 --- a/boards/matek/h743-mini/default.px4board +++ b/boards/matek/h743-mini/default.px4board @@ -30,7 +30,7 @@ CONFIG_MODULES_EKF2=y CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/matek/h743-slim/default.px4board b/boards/matek/h743-slim/default.px4board index b4fe01dbdf..9cf0909725 100644 --- a/boards/matek/h743-slim/default.px4board +++ b/boards/matek/h743-slim/default.px4board @@ -33,7 +33,7 @@ CONFIG_MODULES_EKF2=y CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/matek/h743/default.px4board b/boards/matek/h743/default.px4board index c530e5303d..e61c9b6014 100644 --- a/boards/matek/h743/default.px4board +++ b/boards/matek/h743/default.px4board @@ -32,7 +32,7 @@ CONFIG_MODULES_EKF2=y CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/micoair/h743-aio/default.px4board b/boards/micoair/h743-aio/default.px4board index 7af585274e..5e68a6dbc5 100644 --- a/boards/micoair/h743-aio/default.px4board +++ b/boards/micoair/h743-aio/default.px4board @@ -39,7 +39,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/micoair/h743-v2/default.px4board b/boards/micoair/h743-v2/default.px4board index 518132aa8d..821021a753 100644 --- a/boards/micoair/h743-v2/default.px4board +++ b/boards/micoair/h743-v2/default.px4board @@ -40,7 +40,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/micoair/h743/default.px4board b/boards/micoair/h743/default.px4board index 207bb39bbb..ac84a53cd6 100644 --- a/boards/micoair/h743/default.px4board +++ b/boards/micoair/h743/default.px4board @@ -38,7 +38,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/modalai/fc-v1/default.px4board b/boards/modalai/fc-v1/default.px4board index 7f60b557f2..12623c2c87 100644 --- a/boards/modalai/fc-v1/default.px4board +++ b/boards/modalai/fc-v1/default.px4board @@ -49,7 +49,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index b97c988067..38a9641d33 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -40,7 +40,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/ctrl-zero-classic/default.px4board b/boards/mro/ctrl-zero-classic/default.px4board index 86cadee29a..16cac64d3f 100644 --- a/boards/mro/ctrl-zero-classic/default.px4board +++ b/boards/mro/ctrl-zero-classic/default.px4board @@ -46,7 +46,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/ctrl-zero-f7-oem/default.px4board b/boards/mro/ctrl-zero-f7-oem/default.px4board index 13ee784818..5d35d0b04f 100644 --- a/boards/mro/ctrl-zero-f7-oem/default.px4board +++ b/boards/mro/ctrl-zero-f7-oem/default.px4board @@ -44,7 +44,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/ctrl-zero-f7/default.px4board b/boards/mro/ctrl-zero-f7/default.px4board index e9ad953550..8e33ae6bb9 100644 --- a/boards/mro/ctrl-zero-f7/default.px4board +++ b/boards/mro/ctrl-zero-f7/default.px4board @@ -44,7 +44,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/ctrl-zero-h7-oem/default.px4board b/boards/mro/ctrl-zero-h7-oem/default.px4board index 643c4f1a8a..bbb20fd252 100644 --- a/boards/mro/ctrl-zero-h7-oem/default.px4board +++ b/boards/mro/ctrl-zero-h7-oem/default.px4board @@ -42,7 +42,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/ctrl-zero-h7/default.px4board b/boards/mro/ctrl-zero-h7/default.px4board index 368709da9b..d858efba21 100644 --- a/boards/mro/ctrl-zero-h7/default.px4board +++ b/boards/mro/ctrl-zero-h7/default.px4board @@ -43,7 +43,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index 46d5ac549b..77c80f8de4 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -43,7 +43,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/x21-777/default.px4board b/boards/mro/x21-777/default.px4board index c5c5f82b98..8512dd375e 100644 --- a/boards/mro/x21-777/default.px4board +++ b/boards/mro/x21-777/default.px4board @@ -45,7 +45,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/mro/x21/default.px4board b/boards/mro/x21/default.px4board index dd3a6b85f2..749c36e211 100644 --- a/boards/mro/x21/default.px4board +++ b/boards/mro/x21/default.px4board @@ -46,7 +46,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/nxp/fmuk66-e/default.px4board b/boards/nxp/fmuk66-e/default.px4board index d140a687d5..70f4c16968 100644 --- a/boards/nxp/fmuk66-e/default.px4board +++ b/boards/nxp/fmuk66-e/default.px4board @@ -47,7 +47,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/nxp/fmuk66-v3/default.px4board b/boards/nxp/fmuk66-v3/default.px4board index 40ca30a25e..a8edef6f01 100644 --- a/boards/nxp/fmuk66-v3/default.px4board +++ b/boards/nxp/fmuk66-v3/default.px4board @@ -48,7 +48,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/nxp/mr-canhubk3/fmu.px4board b/boards/nxp/mr-canhubk3/fmu.px4board index c681da011b..a1a3d9ddd1 100644 --- a/boards/nxp/mr-canhubk3/fmu.px4board +++ b/boards/nxp/mr-canhubk3/fmu.px4board @@ -33,7 +33,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/nxp/mr-canhubk3/sysview.px4board b/boards/nxp/mr-canhubk3/sysview.px4board index cf687fcfb9..a101423cf9 100644 --- a/boards/nxp/mr-canhubk3/sysview.px4board +++ b/boards/nxp/mr-canhubk3/sysview.px4board @@ -20,7 +20,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/nxp/mr-canhubk3/zenoh.px4board b/boards/nxp/mr-canhubk3/zenoh.px4board index 8d4876a99f..9bc71357c4 100644 --- a/boards/nxp/mr-canhubk3/zenoh.px4board +++ b/boards/nxp/mr-canhubk3/zenoh.px4board @@ -24,7 +24,7 @@ CONFIG_MODULES_ESC_BATTERY=y CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GYRO_CALIBRATION=y diff --git a/boards/nxp/tropic-community/default.px4board b/boards/nxp/tropic-community/default.px4board index c1beb1fafd..93e80bba11 100644 --- a/boards/nxp/tropic-community/default.px4board +++ b/boards/nxp/tropic-community/default.px4board @@ -47,7 +47,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v2/fixedwing.px4board b/boards/px4/fmu-v2/fixedwing.px4board index 3449d56615..b6fd9c743b 100644 --- a/boards/px4/fmu-v2/fixedwing.px4board +++ b/boards/px4/fmu-v2/fixedwing.px4board @@ -8,6 +8,6 @@ CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y CONFIG_MODULES_AIRSPEED_SELECTOR=y CONFIG_MODULES_FW_ATT_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index bd268cbe2f..386b363aa6 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -51,7 +51,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v4/default.px4board b/boards/px4/fmu-v4/default.px4board index bec469793e..48ecf1b2c2 100644 --- a/boards/px4/fmu-v4/default.px4board +++ b/boards/px4/fmu-v4/default.px4board @@ -52,7 +52,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v4pro/default.px4board b/boards/px4/fmu-v4pro/default.px4board index d090ffb140..a30e386ea9 100644 --- a/boards/px4/fmu-v4pro/default.px4board +++ b/boards/px4/fmu-v4pro/default.px4board @@ -47,7 +47,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index 13bcff46a6..e5da7855a7 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -55,7 +55,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v5/protected.px4board b/boards/px4/fmu-v5/protected.px4board index 99c5c497f6..9f8eb32888 100644 --- a/boards/px4/fmu-v5/protected.px4board +++ b/boards/px4/fmu-v5/protected.px4board @@ -17,7 +17,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=n CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n diff --git a/boards/px4/fmu-v5/rover.px4board b/boards/px4/fmu-v5/rover.px4board index 5fa964bc3a..1d4d56e9a7 100644 --- a/boards/px4/fmu-v5/rover.px4board +++ b/boards/px4/fmu-v5/rover.px4board @@ -4,7 +4,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n diff --git a/boards/px4/fmu-v5/stackcheck.px4board b/boards/px4/fmu-v5/stackcheck.px4board index b182a1c83a..8e96a2ff79 100644 --- a/boards/px4/fmu-v5/stackcheck.px4board +++ b/boards/px4/fmu-v5/stackcheck.px4board @@ -29,7 +29,7 @@ CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_EVENTS=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_GIMBAL=n diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 9115b13ad7..77a92afc7f 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -59,7 +59,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v5x/rover.px4board b/boards/px4/fmu-v5x/rover.px4board index 2490c28c6b..916b009897 100644 --- a/boards/px4/fmu-v5x/rover.px4board +++ b/boards/px4/fmu-v5x/rover.px4board @@ -3,7 +3,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n diff --git a/boards/px4/fmu-v6c/default.px4board b/boards/px4/fmu-v6c/default.px4board index e32ec2e54b..e3aa477534 100644 --- a/boards/px4/fmu-v6c/default.px4board +++ b/boards/px4/fmu-v6c/default.px4board @@ -47,7 +47,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v6c/rover.px4board b/boards/px4/fmu-v6c/rover.px4board index ee7cddbe05..ee2e5a13e5 100644 --- a/boards/px4/fmu-v6c/rover.px4board +++ b/boards/px4/fmu-v6c/rover.px4board @@ -2,7 +2,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n diff --git a/boards/px4/fmu-v6u/default.px4board b/boards/px4/fmu-v6u/default.px4board index 55d857d697..e72a584fd8 100644 --- a/boards/px4/fmu-v6u/default.px4board +++ b/boards/px4/fmu-v6u/default.px4board @@ -47,7 +47,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v6u/rover.px4board b/boards/px4/fmu-v6u/rover.px4board index ee7cddbe05..ee2e5a13e5 100644 --- a/boards/px4/fmu-v6u/rover.px4board +++ b/boards/px4/fmu-v6u/rover.px4board @@ -2,7 +2,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 901318cf30..778eb50198 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -57,7 +57,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v6x/multicopter.px4board b/boards/px4/fmu-v6x/multicopter.px4board index b501d6fe4a..147297d55e 100644 --- a/boards/px4/fmu-v6x/multicopter.px4board +++ b/boards/px4/fmu-v6x/multicopter.px4board @@ -3,7 +3,7 @@ CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=n CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n diff --git a/boards/px4/fmu-v6x/rover.px4board b/boards/px4/fmu-v6x/rover.px4board index ee7cddbe05..ee2e5a13e5 100644 --- a/boards/px4/fmu-v6x/rover.px4board +++ b/boards/px4/fmu-v6x/rover.px4board @@ -2,7 +2,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 6710e97b6a..b990cc48ae 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -57,7 +57,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/fmu-v6xrt/rover.px4board b/boards/px4/fmu-v6xrt/rover.px4board index f7af280b03..458ebe7d08 100644 --- a/boards/px4/fmu-v6xrt/rover.px4board +++ b/boards/px4/fmu-v6xrt/rover.px4board @@ -3,7 +3,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n diff --git a/boards/px4/raspberrypi/default.px4board b/boards/px4/raspberrypi/default.px4board index c8034269aa..484a66beff 100644 --- a/boards/px4/raspberrypi/default.px4board +++ b/boards/px4/raspberrypi/default.px4board @@ -30,7 +30,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index 7da14ff720..28c16f931f 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -19,7 +19,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_FIGURE_OF_EIGHT=y CONFIG_MODULES_FW_RATE_CONTROL=y diff --git a/boards/px4/sitl/spacecraft.px4board b/boards/px4/sitl/spacecraft.px4board index 121c7ca9f7..44ac04d7dd 100644 --- a/boards/px4/sitl/spacecraft.px4board +++ b/boards/px4/sitl/spacecraft.px4board @@ -2,7 +2,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n CONFIG_MODULES_FLIGHT_MODE_MANAGER=n CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y diff --git a/boards/scumaker/pilotpi/default.px4board b/boards/scumaker/pilotpi/default.px4board index 8e18d35c46..d9d35ab25d 100644 --- a/boards/scumaker/pilotpi/default.px4board +++ b/boards/scumaker/pilotpi/default.px4board @@ -32,7 +32,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/siyi/n7/default.px4board b/boards/siyi/n7/default.px4board index a532e87e99..3dafcc85a1 100644 --- a/boards/siyi/n7/default.px4board +++ b/boards/siyi/n7/default.px4board @@ -38,7 +38,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index 7b2a0d7a90..b2cd40a7ba 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -46,7 +46,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/thepeach/k1/default.px4board b/boards/thepeach/k1/default.px4board index 448268f416..cc519b968d 100644 --- a/boards/thepeach/k1/default.px4board +++ b/boards/thepeach/k1/default.px4board @@ -44,7 +44,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/thepeach/r1/default.px4board b/boards/thepeach/r1/default.px4board index 448268f416..cc519b968d 100644 --- a/boards/thepeach/r1/default.px4board +++ b/boards/thepeach/r1/default.px4board @@ -44,7 +44,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/x-mav/ap-h743v2/default.px4board b/boards/x-mav/ap-h743v2/default.px4board index ccb5fe5396..33f81262d3 100644 --- a/boards/x-mav/ap-h743v2/default.px4board +++ b/boards/x-mav/ap-h743v2/default.px4board @@ -40,7 +40,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/boards/zeroone/x6/default.px4board b/boards/zeroone/x6/default.px4board index 85b3a9e993..20677f9d1f 100644 --- a/boards/zeroone/x6/default.px4board +++ b/boards/zeroone/x6/default.px4board @@ -47,7 +47,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y diff --git a/posix-configs/SITL/init/test/test_shutdown b/posix-configs/SITL/init/test/test_shutdown index c61c43c0e2..2a00520ab9 100644 --- a/posix-configs/SITL/init/test/test_shutdown +++ b/posix-configs/SITL/init/test/test_shutdown @@ -29,7 +29,7 @@ flight_mode_manager start mc_pos_control start vtol mc_att_control start vtol mc_rate_control start vtol -fw_pos_control start +fw_mode_manager start fw_lat_lon_control start fw_att_control start vtol airspeed_selector start @@ -60,7 +60,7 @@ flight_mode_manager status mc_pos_control status mc_att_control status mc_rate_control status -fw_pos_control status +fw_mode_manager status fw_att_control status airspeed_selector status dataman status @@ -75,7 +75,7 @@ mc_att_control stop fw_att_control stop flight_mode_manager stop mc_pos_control stop -fw_pos_control stop +fw_mode_manager stop navigator stop commander stop land_detector stop diff --git a/posix-configs/bbblue/px4_fw.config b/posix-configs/bbblue/px4_fw.config index cf8bd9fef6..0d952b84cc 100644 --- a/posix-configs/bbblue/px4_fw.config +++ b/posix-configs/bbblue/px4_fw.config @@ -56,7 +56,7 @@ ekf2 start land_detector start fixedwing fw_att_control start -fw_pos_control start +fw_mode_manager start fw_lat_lon_control start mavlink start -n SoftAp -x -u 14556 -r 1000000 -p diff --git a/posix-configs/rpi/pilotpi_fw.config b/posix-configs/rpi/pilotpi_fw.config index a4fdf0f6fd..4c66381e1c 100644 --- a/posix-configs/rpi/pilotpi_fw.config +++ b/posix-configs/rpi/pilotpi_fw.config @@ -63,7 +63,8 @@ airspeed_selector start land_detector start fixedwing flight_mode_manager start fw_att_control start -fw_pos_control start +fw_mode_manager start +fw_lat_lon_control start mavlink start -x -u 14556 -r 1000000 -p diff --git a/posix-configs/rpi/px4_fw.config b/posix-configs/rpi/px4_fw.config index 74f59a3eb1..5de9619fc8 100644 --- a/posix-configs/rpi/px4_fw.config +++ b/posix-configs/rpi/px4_fw.config @@ -41,7 +41,7 @@ navigator start ekf2 start land_detector start fixedwing fw_att_control start -fw_pos_control start +fw_mode_manager start fw_lat_lon_control start mavlink start -x -u 14556 -r 1000000 -p diff --git a/src/modules/fw_pos_control/CMakeLists.txt b/src/modules/fw_mode_manager/CMakeLists.txt similarity index 92% rename from src/modules/fw_pos_control/CMakeLists.txt rename to src/modules/fw_mode_manager/CMakeLists.txt index 163cf17e67..3e21a51ee1 100644 --- a/src/modules/fw_pos_control/CMakeLists.txt +++ b/src/modules/fw_mode_manager/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2015-2017 PX4 Development Team. All rights reserved. +# Copyright (c) 2015-2025 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -55,11 +55,11 @@ endif() px4_add_module( - MODULE modules__fw_pos_control - MAIN fw_pos_control + MODULE modules__fw_mode_manager + MAIN fw_mode_manager SRCS - FixedwingPositionControl.cpp - FixedwingPositionControl.hpp + FixedWingModeManager.cpp + FixedWingModeManager.hpp ControllerConfigurationHandler.cpp ControllerConfigurationHandler.hpp DEPENDS diff --git a/src/modules/fw_pos_control/ControllerConfigurationHandler.cpp b/src/modules/fw_mode_manager/ControllerConfigurationHandler.cpp similarity index 100% rename from src/modules/fw_pos_control/ControllerConfigurationHandler.cpp rename to src/modules/fw_mode_manager/ControllerConfigurationHandler.cpp diff --git a/src/modules/fw_pos_control/ControllerConfigurationHandler.hpp b/src/modules/fw_mode_manager/ControllerConfigurationHandler.hpp similarity index 100% rename from src/modules/fw_pos_control/ControllerConfigurationHandler.hpp rename to src/modules/fw_mode_manager/ControllerConfigurationHandler.hpp diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_mode_manager/FixedWingModeManager.cpp similarity index 94% rename from src/modules/fw_pos_control/FixedwingPositionControl.cpp rename to src/modules/fw_mode_manager/FixedWingModeManager.cpp index eb9472eae4..57eef702d8 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.cpp @@ -31,7 +31,7 @@ * ****************************************************************************/ -#include "FixedwingPositionControl.hpp" +#include "FixedWingModeManager.hpp" #include #include @@ -52,7 +52,7 @@ using matrix::wrap_pi; const fixed_wing_lateral_setpoint_s empty_lateral_control_setpoint = {.timestamp = 0, .course = NAN, .airspeed_direction = NAN, .lateral_acceleration = NAN}; const fixed_wing_longitudinal_setpoint_s empty_longitudinal_control_setpoint = {.timestamp = 0, .altitude = NAN, .height_rate = NAN, .equivalent_airspeed = NAN, .pitch_direct = NAN, .throttle_direct = NAN}; -FixedwingPositionControl::FixedwingPositionControl() : +FixedWingModeManager::FixedWingModeManager() : ModuleParams(nullptr), WorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers), _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")), @@ -76,13 +76,13 @@ FixedwingPositionControl::FixedwingPositionControl() : parameters_update(); } -FixedwingPositionControl::~FixedwingPositionControl() +FixedWingModeManager::~FixedWingModeManager() { perf_free(_loop_perf); } bool -FixedwingPositionControl::init() +FixedWingModeManager::init() { if (!_local_pos_sub.registerCallback()) { PX4_ERR("callback registration failed"); @@ -93,7 +93,7 @@ FixedwingPositionControl::init() } void -FixedwingPositionControl::parameters_update() +FixedWingModeManager::parameters_update() { updateParams(); @@ -107,7 +107,7 @@ FixedwingPositionControl::parameters_update() } void -FixedwingPositionControl::vehicle_control_mode_poll() +FixedWingModeManager::vehicle_control_mode_poll() { if (_control_mode_sub.updated()) { const bool was_armed = _control_mode.flag_armed; @@ -124,7 +124,7 @@ FixedwingPositionControl::vehicle_control_mode_poll() } void -FixedwingPositionControl::vehicle_command_poll() +FixedWingModeManager::vehicle_command_poll() { vehicle_command_s vehicle_command; @@ -158,7 +158,7 @@ FixedwingPositionControl::vehicle_command_poll() } void -FixedwingPositionControl::airspeed_poll() +FixedWingModeManager::airspeed_poll() { airspeed_validated_s airspeed_validated; @@ -178,7 +178,7 @@ FixedwingPositionControl::airspeed_poll() } void -FixedwingPositionControl::wind_poll(const hrt_abstime now) +FixedWingModeManager::wind_poll(const hrt_abstime now) { if (_wind_sub.updated()) { wind_s wind; @@ -205,7 +205,7 @@ FixedwingPositionControl::wind_poll(const hrt_abstime now) } void -FixedwingPositionControl::manual_control_setpoint_poll() +FixedWingModeManager::manual_control_setpoint_poll() { _manual_control_setpoint_sub.update(&_manual_control_setpoint); @@ -228,7 +228,7 @@ FixedwingPositionControl::manual_control_setpoint_poll() } void -FixedwingPositionControl::vehicle_attitude_poll() +FixedWingModeManager::vehicle_attitude_poll() { vehicle_attitude_s vehicle_attitude; @@ -263,7 +263,7 @@ FixedwingPositionControl::vehicle_attitude_poll() } float -FixedwingPositionControl::get_manual_airspeed_setpoint() +FixedWingModeManager::get_manual_airspeed_setpoint() { float manual_airspeed_setpoint = NAN; @@ -282,7 +282,7 @@ FixedwingPositionControl::get_manual_airspeed_setpoint() } void -FixedwingPositionControl::landing_status_publish() +FixedWingModeManager::landing_status_publish() { position_controller_landing_status_s pos_ctrl_landing_status = {}; @@ -295,7 +295,7 @@ FixedwingPositionControl::landing_status_publish() } void -FixedwingPositionControl::updateLandingAbortStatus(const uint8_t new_abort_status) +FixedWingModeManager::updateLandingAbortStatus(const uint8_t new_abort_status) { // prevent automatic aborts if already flaring, but allow manual aborts if (!_flare_states.flaring || new_abort_status == position_controller_landing_status_s::ABORTED_BY_OPERATOR) { @@ -336,7 +336,7 @@ FixedwingPositionControl::updateLandingAbortStatus(const uint8_t new_abort_statu } float -FixedwingPositionControl::getManualHeightRateSetpoint() +FixedWingModeManager::getManualHeightRateSetpoint() { float height_rate_setpoint = 0.f; @@ -353,7 +353,7 @@ FixedwingPositionControl::getManualHeightRateSetpoint() } void -FixedwingPositionControl::updateManualTakeoffStatus() +FixedWingModeManager::updateManualTakeoffStatus() { if (!_completed_manual_takeoff) { const bool at_controllable_airspeed = _airspeed_eas > _param_fw_airspd_min.get() @@ -365,7 +365,7 @@ FixedwingPositionControl::updateManualTakeoffStatus() } void -FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) +FixedWingModeManager::set_control_mode_current(const hrt_abstime &now) { /* only run position controller in fixed-wing mode and during transitions for VTOL */ if (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !_vehicle_status.in_transition_mode) { @@ -493,7 +493,7 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now) } void -FixedwingPositionControl::update_in_air_states(const hrt_abstime now) +FixedWingModeManager::update_in_air_states(const hrt_abstime now) { /* reset flag when airplane landed */ if (_landed) { @@ -502,7 +502,7 @@ FixedwingPositionControl::update_in_air_states(const hrt_abstime now) } void -FixedwingPositionControl::move_position_setpoint_for_vtol_transition(position_setpoint_s ¤t_sp) +FixedWingModeManager::move_position_setpoint_for_vtol_transition(position_setpoint_s ¤t_sp) { // TODO: velocity, altitude, or just a heading hold position mode should be used for this, not position // shifting hacks @@ -535,9 +535,9 @@ FixedwingPositionControl::move_position_setpoint_for_vtol_transition(position_se } void -FixedwingPositionControl::control_auto(const float control_interval, const Vector2d &curr_pos, - const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr, - const position_setpoint_s &pos_sp_next) +FixedWingModeManager::control_auto(const float control_interval, const Vector2d &curr_pos, + const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr, + const position_setpoint_s &pos_sp_next) { position_setpoint_s current_sp = pos_sp_curr; move_position_setpoint_for_vtol_transition(current_sp); @@ -605,7 +605,7 @@ FixedwingPositionControl::control_auto(const float control_interval, const Vecto } } -void FixedwingPositionControl::control_idle() +void FixedWingModeManager::control_idle() { const hrt_abstime now = hrt_absolute_time(); fixed_wing_lateral_setpoint_s lateral_ctrl_sp {empty_lateral_control_setpoint}; @@ -624,7 +624,7 @@ void FixedwingPositionControl::control_idle() } void -FixedwingPositionControl::control_auto_fixed_bank_alt_hold() +FixedWingModeManager::control_auto_fixed_bank_alt_hold() { const hrt_abstime now = hrt_absolute_time(); const fixed_wing_longitudinal_setpoint_s fw_longitudinal_control_sp = { @@ -656,7 +656,7 @@ FixedwingPositionControl::control_auto_fixed_bank_alt_hold() } void -FixedwingPositionControl::control_auto_descend() +FixedWingModeManager::control_auto_descend() { // Hard-code descend rate to 0.5m/s. This is a compromise to give the system to recover, // but not letting it drift too far away. @@ -686,7 +686,7 @@ FixedwingPositionControl::control_auto_descend() } uint8_t -FixedwingPositionControl::handle_setpoint_type(const position_setpoint_s &pos_sp_curr, +FixedWingModeManager::handle_setpoint_type(const position_setpoint_s &pos_sp_curr, const position_setpoint_s &pos_sp_next) { uint8_t position_sp_type = pos_sp_curr.type; @@ -737,7 +737,7 @@ FixedwingPositionControl::handle_setpoint_type(const position_setpoint_s &pos_sp } void -FixedwingPositionControl::control_auto_position(const float control_interval, const Vector2d &curr_pos, +FixedWingModeManager::control_auto_position(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr) { const float acc_rad = _directional_guidance.switchDistance(500.0f); @@ -823,7 +823,7 @@ FixedwingPositionControl::control_auto_position(const float control_interval, co } void -FixedwingPositionControl::control_auto_velocity(const float control_interval, const Vector2d &curr_pos, +FixedWingModeManager::control_auto_velocity(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { //Offboard velocity control @@ -860,7 +860,7 @@ FixedwingPositionControl::control_auto_velocity(const float control_interval, co } void -FixedwingPositionControl::control_auto_loiter(const float control_interval, const Vector2d &curr_pos, +FixedWingModeManager::control_auto_loiter(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr, const position_setpoint_s &pos_sp_next) { @@ -955,7 +955,7 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons #ifdef CONFIG_FIGURE_OF_EIGHT void -FixedwingPositionControl::controlAutoFigureEight(const float control_interval, const Vector2d &curr_pos, +FixedWingModeManager::controlAutoFigureEight(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { // airspeed settings @@ -999,7 +999,7 @@ FixedwingPositionControl::controlAutoFigureEight(const float control_interval, c } } -void FixedwingPositionControl::publishFigureEightStatus(const position_setpoint_s pos_sp) +void FixedWingModeManager::publishFigureEightStatus(const position_setpoint_s pos_sp) { figure_eight_status_s figure_eight_status{}; figure_eight_status.timestamp = hrt_absolute_time(); @@ -1016,8 +1016,8 @@ void FixedwingPositionControl::publishFigureEightStatus(const position_setpoint_ #endif // CONFIG_FIGURE_OF_EIGHT void -FixedwingPositionControl::control_auto_path(const float control_interval, const Vector2d &curr_pos, - const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) +FixedWingModeManager::control_auto_path(const float control_interval, const Vector2d &curr_pos, + const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { const float target_airspeed = pos_sp_curr.cruising_speed > FLT_EPSILON ? pos_sp_curr.cruising_speed : NAN; @@ -1057,7 +1057,7 @@ FixedwingPositionControl::control_auto_path(const float control_interval, const } void -FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const float control_interval, +FixedWingModeManager::control_auto_takeoff(const hrt_abstime &now, const float control_interval, const Vector2d &global_position, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { if (!_control_mode.flag_armed) { @@ -1264,7 +1264,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo } void -FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, const float control_interval, +FixedWingModeManager::control_auto_landing_straight(const hrt_abstime &now, const float control_interval, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr) { const float airspeed_land = (_param_fw_lnd_airspd.get() > FLT_EPSILON) ? _param_fw_lnd_airspd.get() : @@ -1471,7 +1471,7 @@ FixedwingPositionControl::control_auto_landing_straight(const hrt_abstime &now, } void -FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, const float control_interval, +FixedWingModeManager::control_auto_landing_circular(const hrt_abstime &now, const float control_interval, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { const float airspeed_land = (_param_fw_lnd_airspd.get() > FLT_EPSILON) ? _param_fw_lnd_airspd.get() : @@ -1635,7 +1635,7 @@ FixedwingPositionControl::control_auto_landing_circular(const hrt_abstime &now, } void -FixedwingPositionControl::control_manual_altitude(const float control_interval, const Vector2d &curr_pos, +FixedWingModeManager::control_manual_altitude(const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed) { updateManualTakeoffStatus(); @@ -1678,7 +1678,7 @@ FixedwingPositionControl::control_manual_altitude(const float control_interval, } void -FixedwingPositionControl::control_manual_position(const hrt_abstime now, const float control_interval, +FixedWingModeManager::control_manual_position(const hrt_abstime now, const float control_interval, const Vector2d &curr_pos, const Vector2f &ground_speed) { @@ -1778,12 +1778,12 @@ FixedwingPositionControl::control_manual_position(const hrt_abstime now, const f } } -float FixedwingPositionControl::rollAngleToLateralAccel(float roll_body) const +float FixedWingModeManager::rollAngleToLateralAccel(float roll_body) const { return tanf(roll_body) * CONSTANTS_ONE_G; } -void FixedwingPositionControl::control_backtransition_heading_hold() +void FixedWingModeManager::control_backtransition_heading_hold() { if (!PX4_ISFINITE(_backtrans_heading)) { _backtrans_heading = _local_pos.heading; @@ -1795,7 +1795,7 @@ void FixedwingPositionControl::control_backtransition_heading_hold() _lateral_ctrl_sp_pub.publish(fw_lateral_ctrl_sp); } -void FixedwingPositionControl::control_backtransition_line_follow(const Vector2f &ground_speed, +void FixedWingModeManager::control_backtransition_line_follow(const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr) { Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; @@ -1821,7 +1821,7 @@ void FixedwingPositionControl::control_backtransition_line_follow(const Vector2f } void -FixedwingPositionControl::Run() +FixedWingModeManager::Run() { if (should_exit()) { _local_pos_sub.unregisterCallback(); @@ -2144,7 +2144,7 @@ FixedwingPositionControl::Run() } void -FixedwingPositionControl::reset_takeoff_state() +FixedWingModeManager::reset_takeoff_state() { _runway_takeoff.reset(); @@ -2156,7 +2156,7 @@ FixedwingPositionControl::reset_takeoff_state() } void -FixedwingPositionControl::reset_landing_state() +FixedWingModeManager::reset_landing_state() { _time_started_landing = 0; @@ -2174,7 +2174,7 @@ FixedwingPositionControl::reset_landing_state() } } -float FixedwingPositionControl::getMaxRollAngleNearGround(const float altitude, const float terrain_altitude) const +float FixedWingModeManager::getMaxRollAngleNearGround(const float altitude, const float terrain_altitude) const { // we want the wings level when at the wing height above ground const float height_above_ground = math::max(altitude - (terrain_altitude + _param_fw_wing_height.get()), 0.0f); @@ -2191,7 +2191,7 @@ float FixedwingPositionControl::getMaxRollAngleNearGround(const float altitude, void -FixedwingPositionControl::initializeAutoLanding(const hrt_abstime &now, const position_setpoint_s &pos_sp_prev, +FixedWingModeManager::initializeAutoLanding(const hrt_abstime &now, const position_setpoint_s &pos_sp_prev, const float land_point_altitude, const Vector2f &local_position, const Vector2f &local_land_point) { if (_time_started_landing == 0) { @@ -2250,7 +2250,7 @@ FixedwingPositionControl::initializeAutoLanding(const hrt_abstime &now, const po } Vector2f -FixedwingPositionControl::calculateTouchdownPosition(const float control_interval, const Vector2f &local_land_position) +FixedWingModeManager::calculateTouchdownPosition(const float control_interval, const Vector2f &local_land_position) { if (fabsf(_manual_control_setpoint.yaw) > MANUAL_TOUCHDOWN_NUDGE_INPUT_DEADZONE && _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled @@ -2272,7 +2272,7 @@ FixedwingPositionControl::calculateTouchdownPosition(const float control_interva } Vector2f -FixedwingPositionControl::calculateLandingApproachVector() const +FixedWingModeManager::calculateLandingApproachVector() const { Vector2f landing_approach_vector = -_landing_approach_entrance_offset_vector; const Vector2f approach_unit_vector = landing_approach_vector.unit_or_zero(); @@ -2294,7 +2294,7 @@ FixedwingPositionControl::calculateLandingApproachVector() const } float -FixedwingPositionControl::getLandingTerrainAltitudeEstimate(const hrt_abstime &now, const float land_point_altitude, +FixedWingModeManager::getLandingTerrainAltitudeEstimate(const hrt_abstime &now, const float land_point_altitude, const bool abort_on_terrain_measurement_timeout, const bool abort_on_terrain_timeout) { if (_param_fw_lnd_useter.get() > TerrainEstimateUseOnLanding::kDisableTerrainEstimation) { @@ -2334,7 +2334,7 @@ FixedwingPositionControl::getLandingTerrainAltitudeEstimate(const hrt_abstime &n return land_point_altitude; } -bool FixedwingPositionControl::checkLandingAbortBitMask(const uint8_t automatic_abort_criteria_bitmask, +bool FixedWingModeManager::checkLandingAbortBitMask(const uint8_t automatic_abort_criteria_bitmask, uint8_t landing_abort_criterion) { // landing abort status contains a manual criterion at abort_status==1, need to subtract 2 to directly compare @@ -2348,7 +2348,7 @@ bool FixedwingPositionControl::checkLandingAbortBitMask(const uint8_t automatic_ return ((1 << landing_abort_criterion) & automatic_abort_criteria_bitmask) == (1 << landing_abort_criterion); } -void FixedwingPositionControl::publishLocalPositionSetpoint(const position_setpoint_s ¤t_waypoint) +void FixedWingModeManager::publishLocalPositionSetpoint(const position_setpoint_s ¤t_waypoint) { vehicle_local_position_setpoint_s local_position_setpoint{}; local_position_setpoint.timestamp = hrt_absolute_time(); @@ -2371,7 +2371,7 @@ void FixedwingPositionControl::publishLocalPositionSetpoint(const position_setpo _local_pos_sp_pub.publish(local_position_setpoint); } -void FixedwingPositionControl::publishOrbitStatus(const position_setpoint_s pos_sp) +void FixedWingModeManager::publishOrbitStatus(const position_setpoint_s pos_sp) { orbit_status_s orbit_status{}; orbit_status.timestamp = hrt_absolute_time(); @@ -2390,7 +2390,7 @@ void FixedwingPositionControl::publishOrbitStatus(const position_setpoint_s pos_ _orbit_status_pub.publish(orbit_status); } -DirectionalGuidanceOutput FixedwingPositionControl::navigateWaypoints(const Vector2f &start_waypoint, +DirectionalGuidanceOutput FixedWingModeManager::navigateWaypoints(const Vector2f &start_waypoint, const Vector2f &end_waypoint, const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { @@ -2423,7 +2423,7 @@ DirectionalGuidanceOutput FixedwingPositionControl::navigateWaypoints(const Vect return navigateLine(start_waypoint, end_waypoint, vehicle_pos, ground_vel, wind_vel); } -DirectionalGuidanceOutput FixedwingPositionControl::navigateWaypoint(const Vector2f &waypoint_pos, +DirectionalGuidanceOutput FixedWingModeManager::navigateWaypoint(const Vector2f &waypoint_pos, const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { @@ -2444,7 +2444,7 @@ DirectionalGuidanceOutput FixedwingPositionControl::navigateWaypoint(const Vecto return sp; } -DirectionalGuidanceOutput FixedwingPositionControl::navigateLine(const Vector2f &point_on_line_1, +DirectionalGuidanceOutput FixedWingModeManager::navigateLine(const Vector2f &point_on_line_1, const Vector2f &point_on_line_2, const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { @@ -2468,7 +2468,7 @@ DirectionalGuidanceOutput FixedwingPositionControl::navigateLine(const Vector2f return sp; } -DirectionalGuidanceOutput FixedwingPositionControl::navigateLine(const Vector2f &point_on_line, +DirectionalGuidanceOutput FixedWingModeManager::navigateLine(const Vector2f &point_on_line, const float line_bearing, const Vector2f &vehicle_pos, const Vector2f &ground_vel, const Vector2f &wind_vel) { @@ -2485,7 +2485,7 @@ DirectionalGuidanceOutput FixedwingPositionControl::navigateLine(const Vector2f return sp; } -DirectionalGuidanceOutput FixedwingPositionControl::navigateLoiter(const Vector2f &loiter_center, +DirectionalGuidanceOutput FixedWingModeManager::navigateLoiter(const Vector2f &loiter_center, const Vector2f &vehicle_pos, float radius, bool loiter_direction_counter_clockwise, const Vector2f &ground_vel, const Vector2f &wind_vel) { @@ -2524,7 +2524,7 @@ DirectionalGuidanceOutput FixedwingPositionControl::navigateLoiter(const Vector2 loiter_center + unit_vec_center_to_closest_pt * radius, path_curvature); } -DirectionalGuidanceOutput FixedwingPositionControl::navigatePathTangent(const matrix::Vector2f &vehicle_pos, +DirectionalGuidanceOutput FixedWingModeManager::navigatePathTangent(const matrix::Vector2f &vehicle_pos, const matrix::Vector2f &position_setpoint, const matrix::Vector2f &tangent_setpoint, const matrix::Vector2f &ground_vel, const matrix::Vector2f &wind_vel, const float &curvature) @@ -2541,7 +2541,7 @@ DirectionalGuidanceOutput FixedwingPositionControl::navigatePathTangent(const ma curvature); } -DirectionalGuidanceOutput FixedwingPositionControl::navigateBearing(const matrix::Vector2f &vehicle_pos, float bearing, +DirectionalGuidanceOutput FixedWingModeManager::navigateBearing(const matrix::Vector2f &vehicle_pos, float bearing, const Vector2f &ground_vel, const Vector2f &wind_vel) { const Vector2f unit_path_tangent = Vector2f{cosf(bearing), sinf(bearing)}; @@ -2549,7 +2549,7 @@ DirectionalGuidanceOutput FixedwingPositionControl::navigateBearing(const matrix return _directional_guidance.guideToPath(vehicle_pos, ground_vel, wind_vel, unit_path_tangent, vehicle_pos, 0.0f); } -void FixedwingPositionControl::publish_lateral_guidance_status(const hrt_abstime now) +void FixedWingModeManager::publish_lateral_guidance_status(const hrt_abstime now) { fixed_wing_lateral_guidance_status_s fixed_wing_lateral_guidance_status{}; @@ -2566,9 +2566,9 @@ void FixedwingPositionControl::publish_lateral_guidance_status(const hrt_abstime _fixed_wing_lateral_guidance_status_pub.publish(fixed_wing_lateral_guidance_status); } -int FixedwingPositionControl::task_spawn(int argc, char *argv[]) +int FixedWingModeManager::task_spawn(int argc, char *argv[]) { - FixedwingPositionControl *instance = new FixedwingPositionControl(); + FixedWingModeManager *instance = new FixedWingModeManager(); if (instance) { _object.store(instance); @@ -2589,12 +2589,12 @@ int FixedwingPositionControl::task_spawn(int argc, char *argv[]) return PX4_ERROR; } -int FixedwingPositionControl::custom_command(int argc, char *argv[]) +int FixedWingModeManager::custom_command(int argc, char *argv[]) { return print_usage("unknown command"); } -int FixedwingPositionControl::print_usage(const char *reason) +int FixedWingModeManager::print_usage(const char *reason) { if (reason) { PX4_WARN("%s\n", reason); @@ -2603,18 +2603,20 @@ int FixedwingPositionControl::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description -fw_pos_control is the fixed-wing position controller. +This implements the setpoint generation for all PX4-internal fixed-wing modes, height-rate control and higher. +It takes the current mode state of the vehicle as input and outputs setpoints consumed by the fixed-wing +lateral-longitudinal controller and and controllers below that (attitude, rate). )DESCR_STR"); - PRINT_MODULE_USAGE_NAME("fw_pos_control", "controller"); + PRINT_MODULE_USAGE_NAME("fw_mode_manager", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; } -extern "C" __EXPORT int fw_pos_control_main(int argc, char *argv[]) +extern "C" __EXPORT int fw_mode_manager_main(int argc, char *argv[]) { - return FixedwingPositionControl::main(argc, argv); + return FixedWingModeManager::main(argc, argv); } diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.hpp b/src/modules/fw_mode_manager/FixedWingModeManager.hpp similarity index 98% rename from src/modules/fw_pos_control/FixedwingPositionControl.hpp rename to src/modules/fw_mode_manager/FixedWingModeManager.hpp index 33a0cd87e7..81eed7d81f 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.hpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.hpp @@ -33,12 +33,12 @@ /** - * @file FixedwingPositionControl.hpp - * Implementation of various fixed-wing position level navigation/control modes. + * @file FixedWingModeManager.hpp + * Implementation of various fixed-wing control modes. */ -#ifndef FIXEDWINGPOSITIONCONTROL_HPP_ -#define FIXEDWINGPOSITIONCONTROL_HPP_ +#ifndef FIXEDWINGMODEMANAGER_HPP_ +#define FIXEDWINGMODEMANAGER_HPP_ #include "launchdetection/LaunchDetector.h" #include "runway_takeoff/RunwayTakeoff.h" @@ -151,12 +151,12 @@ static constexpr float POST_TOUCHDOWN_CLAMP_TIME = 0.5f; // [] Stick deadzon static constexpr float kStickDeadBand = 0.06f; -class FixedwingPositionControl final : public ModuleBase, public ModuleParams, +class FixedWingModeManager final : public ModuleBase, public ModuleParams, public px4::WorkItem { public: - FixedwingPositionControl(); - ~FixedwingPositionControl() override; + FixedWingModeManager(); + ~FixedWingModeManager() override; /** @see ModuleBase */ static int task_spawn(int argc, char *argv[]); @@ -872,4 +872,4 @@ private: ) }; -#endif // FIXEDWINGPOSITIONCONTROL_HPP_ +#endif // FIXEDWINGMODEMANAGER_HPP_ diff --git a/src/modules/fw_mode_manager/Kconfig b/src/modules/fw_mode_manager/Kconfig new file mode 100644 index 0000000000..b0c2689413 --- /dev/null +++ b/src/modules/fw_mode_manager/Kconfig @@ -0,0 +1,20 @@ +menuconfig MODULES_FW_MODE_MANAGER + bool "fw_mode_manager" + default n + ---help--- + Enable support for fw_mode_manager + +menuconfig USER_FW_MODE_MANAGER + bool "fw_mode_manager running as userspace module" + default n + depends on BOARD_PROTECTED && MODULES_FW_MODE_MANAGER + ---help--- + Put fw_mode_manager in userspace memory + +menuconfig FIGURE_OF_EIGHT + bool "fw_mode_manager figure of eight loiter support" + default n + depends on MODULES_FW_MODE_MANAGER + ---help--- + Enable support for the figure of eight loitering pattern in fixed wing. + NOTE: Enable Mavlink development support to get feedback message. diff --git a/src/modules/fw_pos_control/figure_eight/CMakeLists.txt b/src/modules/fw_mode_manager/figure_eight/CMakeLists.txt similarity index 100% rename from src/modules/fw_pos_control/figure_eight/CMakeLists.txt rename to src/modules/fw_mode_manager/figure_eight/CMakeLists.txt diff --git a/src/modules/fw_pos_control/figure_eight/FigureEight.cpp b/src/modules/fw_mode_manager/figure_eight/FigureEight.cpp similarity index 100% rename from src/modules/fw_pos_control/figure_eight/FigureEight.cpp rename to src/modules/fw_mode_manager/figure_eight/FigureEight.cpp diff --git a/src/modules/fw_pos_control/figure_eight/FigureEight.hpp b/src/modules/fw_mode_manager/figure_eight/FigureEight.hpp similarity index 100% rename from src/modules/fw_pos_control/figure_eight/FigureEight.hpp rename to src/modules/fw_mode_manager/figure_eight/FigureEight.hpp diff --git a/src/modules/fw_pos_control/fw_path_navigation_params.c b/src/modules/fw_mode_manager/fw_mode_manager_params.c similarity index 100% rename from src/modules/fw_pos_control/fw_path_navigation_params.c rename to src/modules/fw_mode_manager/fw_mode_manager_params.c diff --git a/src/modules/fw_pos_control/launchdetection/CMakeLists.txt b/src/modules/fw_mode_manager/launchdetection/CMakeLists.txt similarity index 100% rename from src/modules/fw_pos_control/launchdetection/CMakeLists.txt rename to src/modules/fw_mode_manager/launchdetection/CMakeLists.txt diff --git a/src/modules/fw_pos_control/launchdetection/LaunchDetector.cpp b/src/modules/fw_mode_manager/launchdetection/LaunchDetector.cpp similarity index 100% rename from src/modules/fw_pos_control/launchdetection/LaunchDetector.cpp rename to src/modules/fw_mode_manager/launchdetection/LaunchDetector.cpp diff --git a/src/modules/fw_pos_control/launchdetection/LaunchDetector.h b/src/modules/fw_mode_manager/launchdetection/LaunchDetector.h similarity index 100% rename from src/modules/fw_pos_control/launchdetection/LaunchDetector.h rename to src/modules/fw_mode_manager/launchdetection/LaunchDetector.h diff --git a/src/modules/fw_pos_control/launchdetection/launchdetection_params.c b/src/modules/fw_mode_manager/launchdetection/launchdetection_params.c similarity index 100% rename from src/modules/fw_pos_control/launchdetection/launchdetection_params.c rename to src/modules/fw_mode_manager/launchdetection/launchdetection_params.c diff --git a/src/modules/fw_pos_control/runway_takeoff/CMakeLists.txt b/src/modules/fw_mode_manager/runway_takeoff/CMakeLists.txt similarity index 100% rename from src/modules/fw_pos_control/runway_takeoff/CMakeLists.txt rename to src/modules/fw_mode_manager/runway_takeoff/CMakeLists.txt diff --git a/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.cpp b/src/modules/fw_mode_manager/runway_takeoff/RunwayTakeoff.cpp similarity index 100% rename from src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.cpp rename to src/modules/fw_mode_manager/runway_takeoff/RunwayTakeoff.cpp diff --git a/src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.h b/src/modules/fw_mode_manager/runway_takeoff/RunwayTakeoff.h similarity index 100% rename from src/modules/fw_pos_control/runway_takeoff/RunwayTakeoff.h rename to src/modules/fw_mode_manager/runway_takeoff/RunwayTakeoff.h diff --git a/src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c b/src/modules/fw_mode_manager/runway_takeoff/runway_takeoff_params.c similarity index 100% rename from src/modules/fw_pos_control/runway_takeoff/runway_takeoff_params.c rename to src/modules/fw_mode_manager/runway_takeoff/runway_takeoff_params.c diff --git a/src/modules/fw_pos_control/Kconfig b/src/modules/fw_pos_control/Kconfig deleted file mode 100644 index d0bffb8dd8..0000000000 --- a/src/modules/fw_pos_control/Kconfig +++ /dev/null @@ -1,20 +0,0 @@ -menuconfig MODULES_FW_POS_CONTROL - bool "fw_pos_control" - default n - ---help--- - Enable support for fw_pos_control - -menuconfig USER_FW_POS_CONTROL - bool "fw_pos_control running as userspace module" - default n - depends on BOARD_PROTECTED && MODULES_FW_POS_CONTROL - ---help--- - Put fw_pos_control in userspace memory - -menuconfig FIGURE_OF_EIGHT - bool "fw_pos_control figure of eight loiter support" - default n - depends on MODULES_FW_POS_CONTROL - ---help--- - Enable support for the figure of eight loitering pattern in fixed wing. - NOTE: Enable Mavlink development support to get feedback message. From 8a5e5a411a476834f0c667dc1631feb5900efdc2 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Wed, 16 Apr 2025 09:54:21 +0200 Subject: [PATCH 042/130] msgs: Clean up message definitions and descriptions - Add versioning to interfacing messages - Add header description - Add units, frame and range wherever possible - Add [norm] and @range indentifiers --- msg/CMakeLists.txt | 8 ++++---- msg/FixedWingLateralGuidanceStatus.msg | 19 +++++++++++-------- msg/FixedWingLateralSetpoint.msg | 7 ------- msg/FixedWingLateralStatus.msg | 9 ++++++--- msg/FixedWingLongitudinalSetpoint.msg | 9 --------- msg/FixedWingRunwayControl.msg | 2 +- msg/LateralControlConfiguration.msg | 3 --- msg/LongitudinalControlConfiguration.msg | 11 ----------- msg/versioned/FixedWingLateralSetpoint.msg | 11 +++++++++++ .../FixedWingLongitudinalSetpoint.msg | 14 ++++++++++++++ msg/versioned/LateralControlConfiguration.msg | 8 ++++++++ .../LongitudinalControlConfiguration.msg | 17 +++++++++++++++++ .../FwLateralLongitudinalControl.cpp | 2 +- 13 files changed, 73 insertions(+), 47 deletions(-) delete mode 100644 msg/FixedWingLateralSetpoint.msg delete mode 100644 msg/FixedWingLongitudinalSetpoint.msg delete mode 100644 msg/LateralControlConfiguration.msg delete mode 100644 msg/LongitudinalControlConfiguration.msg create mode 100644 msg/versioned/FixedWingLateralSetpoint.msg create mode 100644 msg/versioned/FixedWingLongitudinalSetpoint.msg create mode 100644 msg/versioned/LateralControlConfiguration.msg create mode 100644 msg/versioned/LongitudinalControlConfiguration.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 29af39b27f..a0cc5ab1ec 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -90,8 +90,6 @@ set(msg_files FollowTargetEstimator.msg FollowTargetStatus.msg FuelTankStatus.msg - FixedWingLateralSetpoint.msg - FixedWingLongitudinalSetpoint.msg FixedWingLateralGuidanceStatus.msg FixedWingLateralStatus.msg FixedWingRunwayControl.msg @@ -125,12 +123,10 @@ set(msg_files LandingGearWheel.msg LandingTargetInnovations.msg LandingTargetPose.msg - LateralControlConfiguration.msg LaunchDetectionStatus.msg LedControl.msg LoggerStatus.msg LogMessage.msg - LongitudinalControlConfiguration.msg MagnetometerBiasEstimate.msg MagWorkerData.msg ManualControlSwitches.msg @@ -247,8 +243,12 @@ set(msg_files versioned/ArmingCheckRequest.msg versioned/BatteryStatus.msg versioned/ConfigOverrides.msg + versioned/FixedWingLateralSetpoint.msg + versioned/FixedWingLongitudinalSetpoint.msg versioned/GotoSetpoint.msg versioned/HomePosition.msg + versioned/LateralControlConfiguration.msg + versioned/LongitudinalControlConfiguration.msg versioned/ManualControlSetpoint.msg versioned/ModeCompleted.msg versioned/RegisterExtComponentReply.msg diff --git a/msg/FixedWingLateralGuidanceStatus.msg b/msg/FixedWingLateralGuidanceStatus.msg index 6295f8948e..57a9df5136 100644 --- a/msg/FixedWingLateralGuidanceStatus.msg +++ b/msg/FixedWingLateralGuidanceStatus.msg @@ -1,10 +1,13 @@ +# Fixed Wing Lateral Guidance Status message +# Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + uint64 timestamp # time since system start (microseconds) -float32 course_setpoint # bearing angle (same as course) [rad] -float32 lateral_acceleration_ff # lateral acceleration demand only for maintaining curvature [m/s^2] -float32 bearing_feas # bearing feasibility [0,1] -float32 bearing_feas_on_track # on-track bearing feasibility [0,1] -float32 signed_track_error # signed track error [m] -float32 track_error_bound # track error bound [m] -float32 adapted_period # adapted period (if auto-tuning enabled) [s] -uint8 wind_est_valid # (boolean) true = wind estimate is valid and/or being used by controller (also indicates if wind est usage is disabled despite being valid) +float32 course_setpoint # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. Set by guidance law +float32 lateral_acceleration_ff # [m/s^2] [FRD] lateral acceleration demand only for maintaining curvature +float32 bearing_feas # [@range 0,1] bearing feasibility +float32 bearing_feas_on_track # [@range 0,1] on-track bearing feasibility +float32 signed_track_error # [m] signed track error +float32 track_error_bound # [m] track error bound +float32 adapted_period # [s] adapted period (if auto-tuning enabled) +uint8 wind_est_valid # [boolean] true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) diff --git a/msg/FixedWingLateralSetpoint.msg b/msg/FixedWingLateralSetpoint.msg deleted file mode 100644 index d899993ad5..0000000000 --- a/msg/FixedWingLateralSetpoint.msg +++ /dev/null @@ -1,7 +0,0 @@ -uint64 timestamp - -# NOTE: At least one of course, airspeed_direction, or lateral_acceleration must be finite - -float32 course # [-pi, pi] Course over ground setpoint, w.r.t. North. NAN if not controlled directly. -float32 airspeed_direction # [-pi, pi] Angle projected to ground of desired airspeed vector, w.r.t. North. NAN if not controlled directly, used as feedforward if course setpoint is finite. -float32 lateral_acceleration # [m/s^2] Lateral acceleration setpoint in FRD frame. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. diff --git a/msg/FixedWingLateralStatus.msg b/msg/FixedWingLateralStatus.msg index b877948b24..4843937069 100644 --- a/msg/FixedWingLateralStatus.msg +++ b/msg/FixedWingLateralStatus.msg @@ -1,4 +1,7 @@ -uint64 timestamp # time since system start (microseconds) +# Fixed Wing Lateral Status message +# Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint -float32 lateral_acceleration # resultant lateral acceleration reference [m/s^2] -float32 can_run_factor # estimate of certainty of the correct functionality of the npfg roll setpoint in [0, 1] +uint64 timestamp # time since system start (microseconds) + +float32 lateral_acceleration_setpoint # [m/s^2] [FRD] resultant lateral acceleration setpoint +float32 can_run_factor # [norm] [@range 0, 1] estimate of certainty of the correct functionality of the npfg roll setpoint diff --git a/msg/FixedWingLongitudinalSetpoint.msg b/msg/FixedWingLongitudinalSetpoint.msg deleted file mode 100644 index 25595f76c4..0000000000 --- a/msg/FixedWingLongitudinalSetpoint.msg +++ /dev/null @@ -1,9 +0,0 @@ -uint64 timestamp - -# Note: If not both pitch_direct and throttle_direct are finite, then either altitude or height_rate must be finite - -float32 altitude # [m] Altitude setpoint AMSL, NAN if not controlled -float32 height_rate # [m/s] NAN if not controlled directly, used as feedforward if altitude is finite -float32 equivalent_airspeed # [m/s] NAN if system default should be used -float32 pitch_direct # [rad] NAN if not controlled, overrides total energy controller -float32 throttle_direct # [0,1] NAN if not controlled, overrides total energy controller diff --git a/msg/FixedWingRunwayControl.msg b/msg/FixedWingRunwayControl.msg index a74d702c10..62d09a5ebf 100644 --- a/msg/FixedWingRunwayControl.msg +++ b/msg/FixedWingRunwayControl.msg @@ -5,4 +5,4 @@ uint64 timestamp # [us] time since system start bool wheel_steering_enabled # Flag that enables the wheel steering. -float32 wheel_steering_nudging_rate # [norm] [-1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. +float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. diff --git a/msg/LateralControlConfiguration.msg b/msg/LateralControlConfiguration.msg deleted file mode 100644 index ee96028776..0000000000 --- a/msg/LateralControlConfiguration.msg +++ /dev/null @@ -1,3 +0,0 @@ -uint64 timestamp - -float32 lateral_accel_max # [m/s^2] maps 1:1 to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY diff --git a/msg/LongitudinalControlConfiguration.msg b/msg/LongitudinalControlConfiguration.msg deleted file mode 100644 index 0f944cc9bf..0000000000 --- a/msg/LongitudinalControlConfiguration.msg +++ /dev/null @@ -1,11 +0,0 @@ -uint64 timestamp - -float32 pitch_min # [rad] -float32 pitch_max # [rad] -float32 throttle_min # [0,1] -float32 throttle_max # [0,1] -float32 climb_rate_target # [m/s] target climbrate used to change altitude -float32 sink_rate_target # [m/s] target sinkrate used to change altitude -float32 speed_weight # [0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only -bool enforce_low_height_condition # if true, total energy controller will use lower altitude control time constant -bool disable_underspeed_protection # if true, underspeed handling is disabled in the total energy controller diff --git a/msg/versioned/FixedWingLateralSetpoint.msg b/msg/versioned/FixedWingLateralSetpoint.msg new file mode 100644 index 0000000000..ac7410878e --- /dev/null +++ b/msg/versioned/FixedWingLateralSetpoint.msg @@ -0,0 +1,11 @@ +# Fixed Wing Lateral Setpoint message +# Used by the fw_lateral_longitudinal_control module +# At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. +float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. +float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. diff --git a/msg/versioned/FixedWingLongitudinalSetpoint.msg b/msg/versioned/FixedWingLongitudinalSetpoint.msg new file mode 100644 index 0000000000..06896df8b6 --- /dev/null +++ b/msg/versioned/FixedWingLongitudinalSetpoint.msg @@ -0,0 +1,14 @@ +# Fixed Wing Longitudinal Setpoint message +# Used by the fw_lateral_longitudinal_control module +# If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +# If both altitude and height_rate are NAN, the controller maintains the current altitude. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite +float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not controlled directly +float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used +float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller +float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller diff --git a/msg/versioned/LateralControlConfiguration.msg b/msg/versioned/LateralControlConfiguration.msg new file mode 100644 index 0000000000..783bd38465 --- /dev/null +++ b/msg/versioned/LateralControlConfiguration.msg @@ -0,0 +1,8 @@ +# Fixed Wing Lateral Control Configuration message +# Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY diff --git a/msg/versioned/LongitudinalControlConfiguration.msg b/msg/versioned/LongitudinalControlConfiguration.msg new file mode 100644 index 0000000000..ac9c56df44 --- /dev/null +++ b/msg/versioned/LongitudinalControlConfiguration.msg @@ -0,0 +1,17 @@ +# Fixed Wing Longitudinal Control Configuration message +# Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +# and configure the resultant setpoints. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 pitch_min # [rad][@range -pi, pi] defaults to FW_P_LIM_MIN if NAN. +float32 pitch_max # [rad][@range -pi, pi] defaults to FW_P_LIM_MAX if NAN. +float32 throttle_min # [norm] [@range 0,1] deaults to FW_THR_MIN if NAN. +float32 throttle_max # [norm] [@range 0,1] defaults to FW_THR_MAX if NAN. +float32 climb_rate_target # [m/s] target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only +bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking +bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp index 77e0ae5b23..1c42f5838c 100644 --- a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp @@ -285,7 +285,7 @@ void FwLateralLongitudinalControl::Run() fixed_wing_lateral_status_s fixed_wing_lateral_status{}; fixed_wing_lateral_status.timestamp = hrt_absolute_time(); - fixed_wing_lateral_status.lateral_acceleration = lateral_accel_sp; + fixed_wing_lateral_status.lateral_acceleration_setpoint = lateral_accel_sp; fixed_wing_lateral_status.can_run_factor = _can_run_factor; _fixed_wing_lateral_status_pub.publish(fixed_wing_lateral_status); From ea94bc11eb75f1a840604a1abd45d6ed4a7ac83c Mon Sep 17 00:00:00 2001 From: Silvan Date: Wed, 16 Apr 2025 16:32:12 +0200 Subject: [PATCH 043/130] DDS topics: add FW highlevel interfaces Signed-off-by: Silvan --- src/modules/uxrce_dds_client/dds_topics.yaml | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index 24c30d8850..a1e33be861 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -163,5 +163,17 @@ subscriptions: - topic: /fmu/in/aux_global_position type: px4_msgs::msg::VehicleGlobalPosition + - topic: /fmu/in/fixed_wing_longitudinal_setpoint + type: px4_msgs::msg::FixedWingLongitudinalSetpoint + + - topic: /fmu/in/fixed_wing_lateral_setpoint + type: px4_msgs::msg::FixedWingLateralSetpoint + + - topic: /fmu/in/longitudinal_control_configuration + type: px4_msgs::msg::LongitudinalControlConfiguration + + - topic: /fmu/in/lateral_control_configuration + type: px4_msgs::msg::LateralControlConfiguration + # Create uORB::PublicationMulti subscriptions_multi: From 45540455fe9ddae51af71e6ee129ffebe1d67921 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Mon, 21 Apr 2025 12:35:10 +0200 Subject: [PATCH 044/130] ackermann: separate actuator control --- .../AckermannActControl.cpp | 105 +++++++++++++++++ .../AckermannActControl.hpp | 111 ++++++++++++++++++ .../AckermannActControl/CMakeLists.txt | 38 ++++++ src/modules/rover_ackermann/CMakeLists.txt | 2 + .../rover_ackermann/RoverAckermann.cpp | 80 ++----------- .../rover_ackermann/RoverAckermann.hpp | 42 +------ 6 files changed, 265 insertions(+), 113 deletions(-) create mode 100644 src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp create mode 100644 src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp create mode 100644 src/modules/rover_ackermann/AckermannActControl/CMakeLists.txt diff --git a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp new file mode 100644 index 0000000000..c898186ec7 --- /dev/null +++ b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "AckermannActControl.hpp" + +using namespace time_literals; + +AckermannActControl::AckermannActControl(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); +} + +void AckermannActControl::updateParams() +{ + ModuleParams::updateParams(); + + if (_param_ra_str_rate_limit.get() > FLT_EPSILON && _param_ra_max_str_ang.get() > FLT_EPSILON) { + _servo_setpoint.setSlewRate((M_DEG_TO_RAD_F * _param_ra_str_rate_limit.get()) / _param_ra_max_str_ang.get()); + } + + if (_param_ro_accel_limit.get() > FLT_EPSILON && _param_ro_max_thr_speed.get() > FLT_EPSILON) { + _motor_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get()); + } +} + +void AckermannActControl::updateActControl() +{ + const hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + + generateActuatorSetpoint(); + +} + +void AckermannActControl::generateActuatorSetpoint() +{ + // Motor control + rover_throttle_setpoint_s rover_throttle_setpoint{}; + _rover_throttle_setpoint_sub.copy(&rover_throttle_setpoint); + actuator_motors_s actuator_motors_sub{}; + _actuator_motors_sub.copy(&actuator_motors_sub); + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + actuator_motors.control[0] = RoverControl::throttleControl(_motor_setpoint, + rover_throttle_setpoint.throttle_body_x, actuator_motors_sub.control[0], _param_ro_accel_limit.get(), + _param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), _dt); + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + + // Servo control + rover_steering_setpoint_s rover_steering_setpoint{}; + _rover_steering_setpoint_sub.copy(&rover_steering_setpoint); + actuator_servos_s actuator_servos_sub{}; + _actuator_servos_sub.copy(&actuator_servos_sub); + + if (_param_ra_str_rate_limit.get() > FLT_EPSILON + && _param_ra_max_str_ang.get() > FLT_EPSILON) { // Apply slew rate if configured + if (fabsf(_servo_setpoint.getState() - actuator_servos_sub.control[0]) > fabsf( + rover_steering_setpoint.normalized_steering_angle - + actuator_servos_sub.control[0])) { + _servo_setpoint.setForcedValue(actuator_servos_sub.control[0]); + } + + _servo_setpoint.update(rover_steering_setpoint.normalized_steering_angle, _dt); + + } else { + _servo_setpoint.setForcedValue(rover_steering_setpoint.normalized_steering_angle); + } + + actuator_servos_s actuator_servos{}; + actuator_servos.control[0] = _servo_setpoint.getState(); + actuator_servos.timestamp = _timestamp; + _actuator_servos_pub.publish(actuator_servos); +} diff --git a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp new file mode 100644 index 0000000000..d8933525e3 --- /dev/null +++ b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp @@ -0,0 +1,111 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include +#include + +/** + * @brief Class for ackermann actuator control. + */ +class AckermannActControl : public ModuleParams +{ +public: + /** + * @brief Constructor for AckermannActControl. + * @param parent The parent ModuleParams object. + */ + AckermannActControl(ModuleParams *parent); + ~AckermannActControl() = default; + + /** + * @brief Update actuator controller. + */ + void updateActControl(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + + /** + * @brief Generate and publish actuatorMotors/actuatorServos setpoints from roverThrottleSetpoint/roverSteeringSetpoint. + */ + void generateActuatorSetpoint(); + + // uORB subscriptions + uORB::Subscription _actuator_servos_sub{ORB_ID(actuator_servos)}; + uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; + uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)}; + uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)}; + + // uORB publications + uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _actuator_servos_pub{ORB_ID(actuator_servos)}; + + // Variables + hrt_abstime _timestamp{0}; + float _dt{0.f}; + + // Controllers + SlewRate _servo_setpoint{0.f}; + SlewRate _motor_setpoint{0.f}; + + // Parameters + DEFINE_PARAMETERS( + (ParamInt) _param_r_rev, + (ParamFloat) _param_ra_str_rate_limit, + (ParamFloat) _param_ra_max_str_ang, + (ParamFloat) _param_ro_accel_limit, + (ParamFloat) _param_ro_decel_limit, + (ParamFloat) _param_ro_max_thr_speed + ) +}; diff --git a/src/modules/rover_ackermann/AckermannActControl/CMakeLists.txt b/src/modules/rover_ackermann/AckermannActControl/CMakeLists.txt new file mode 100644 index 0000000000..59c168320c --- /dev/null +++ b/src/modules/rover_ackermann/AckermannActControl/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(AckermannActControl + AckermannActControl.cpp +) + +target_include_directories(AckermannActControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_ackermann/CMakeLists.txt b/src/modules/rover_ackermann/CMakeLists.txt index 957f56d74b..8f71478554 100644 --- a/src/modules/rover_ackermann/CMakeLists.txt +++ b/src/modules/rover_ackermann/CMakeLists.txt @@ -31,6 +31,7 @@ # ############################################################################ +add_subdirectory(AckermannActControl) add_subdirectory(AckermannRateControl) add_subdirectory(AckermannAttControl) add_subdirectory(AckermannVelControl) @@ -43,6 +44,7 @@ px4_add_module( RoverAckermann.cpp RoverAckermann.hpp DEPENDS + AckermannActControl AckermannRateControl AckermannAttControl AckermannVelControl diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index c586741e25..d57d6a0d8c 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -53,14 +53,6 @@ bool RoverAckermann::init() void RoverAckermann::updateParams() { ModuleParams::updateParams(); - - if (_param_ra_str_rate_limit.get() > FLT_EPSILON && _param_ra_max_str_ang.get() > FLT_EPSILON) { - _servo_setpoint.setSlewRate((M_DEG_TO_RAD_F * _param_ra_str_rate_limit.get()) / _param_ra_max_str_ang.get()); - } - - if (_param_ro_accel_limit.get() > FLT_EPSILON && _param_ro_max_thr_speed.get() > FLT_EPSILON) { - _motor_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get()); - } } void RoverAckermann::Run() @@ -69,15 +61,6 @@ void RoverAckermann::Run() updateParams(); } - const hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - - _ackermann_pos_control.updatePosControl(); - _ackermann_vel_control.updateVelControl(); - _ackermann_att_control.updateAttControl(); - _ackermann_rate_control.updateRateControl(); - if (_vehicle_control_mode_sub.updated()) { _vehicle_control_mode_sub.copy(&_vehicle_control_mode); } @@ -90,8 +73,12 @@ void RoverAckermann::Run() generateSteeringAndThrottleSetpoint(); } - generateActuatorSetpoint(); + _ackermann_pos_control.updatePosControl(); + _ackermann_vel_control.updateVelControl(); + _ackermann_att_control.updateAttControl(); + _ackermann_rate_control.updateRateControl(); + _ackermann_act_control.updateActControl(); } void RoverAckermann::generateSteeringAndThrottleSetpoint() @@ -100,70 +87,17 @@ void RoverAckermann::generateSteeringAndThrottleSetpoint() if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = _timestamp; + rover_steering_setpoint.timestamp = hrt_absolute_time(); rover_steering_setpoint.normalized_steering_angle = manual_control_setpoint.roll; _rover_steering_setpoint_pub.publish(rover_steering_setpoint); rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; rover_throttle_setpoint.throttle_body_y = 0.f; _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); } } -void RoverAckermann::generateActuatorSetpoint() -{ - if (_rover_throttle_setpoint_sub.updated()) { - _rover_throttle_setpoint_sub.copy(&_rover_throttle_setpoint); - } - - if (_actuator_motors_sub.updated()) { - actuator_motors_s actuator_motors{}; - _actuator_motors_sub.copy(&actuator_motors); - _current_motor_setpoint = actuator_motors.control[0]; - } - - if (_vehicle_control_mode.flag_armed) { - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); - actuator_motors.control[0] = RoverControl::throttleControl(_motor_setpoint, - _rover_throttle_setpoint.throttle_body_x, _current_motor_setpoint, _param_ro_accel_limit.get(), - _param_ro_decel_limit.get(), - _param_ro_max_thr_speed.get(), _dt); - actuator_motors.timestamp = _timestamp; - _actuator_motors_pub.publish(actuator_motors); - } - - if (_rover_steering_setpoint_sub.updated()) { - _rover_steering_setpoint_sub.copy(&_rover_steering_setpoint); - } - - if (_actuator_servos_sub.updated()) { - actuator_servos_s actuator_servos{}; - _actuator_servos_sub.copy(&actuator_servos); - _current_servo_setpoint = actuator_servos.control[0]; - } - - if (_param_ra_str_rate_limit.get() > FLT_EPSILON - && _param_ra_max_str_ang.get() > FLT_EPSILON) { // Apply slew rate if configured - if (fabsf(_servo_setpoint.getState() - _current_servo_setpoint) > fabsf( - _rover_steering_setpoint.normalized_steering_angle - - _current_servo_setpoint)) { - _servo_setpoint.setForcedValue(_current_servo_setpoint); - } - - _servo_setpoint.update(_rover_steering_setpoint.normalized_steering_angle, _dt); - - } else { - _servo_setpoint.setForcedValue(_rover_steering_setpoint.normalized_steering_angle); - } - - actuator_servos_s actuator_servos{}; - actuator_servos.control[0] = _servo_setpoint.getState(); - actuator_servos.timestamp = _timestamp; - _actuator_servos_pub.publish(actuator_servos); -} - int RoverAckermann::task_spawn(int argc, char *argv[]) { RoverAckermann *instance = new RoverAckermann(); diff --git a/src/modules/rover_ackermann/RoverAckermann.hpp b/src/modules/rover_ackermann/RoverAckermann.hpp index 1a1cd0c987..0655ba9dda 100644 --- a/src/modules/rover_ackermann/RoverAckermann.hpp +++ b/src/modules/rover_ackermann/RoverAckermann.hpp @@ -40,24 +40,17 @@ #include #include -// Libraries -#include -#include -#include - // uORB includes #include #include -#include #include -#include -#include #include #include #include #include // Local includes +#include "AckermannActControl/AckermannActControl.hpp" #include "AckermannRateControl/AckermannRateControl.hpp" #include "AckermannAttControl/AckermannAttControl.hpp" #include "AckermannVelControl/AckermannVelControl.hpp" @@ -98,52 +91,21 @@ private: */ void generateSteeringAndThrottleSetpoint(); - /** - * @brief Generate and publish actuatorMotors/actuatorServos setpoints from roverThrottleSetpoint/roverSteeringSetpoint. - */ - void generateActuatorSetpoint(); - // uORB subscriptions uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; - uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)}; - uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; - uORB::Subscription _actuator_servos_sub{ORB_ID(actuator_servos)}; - uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; vehicle_control_mode_s _vehicle_control_mode{}; - rover_steering_setpoint_s _rover_steering_setpoint{}; - rover_throttle_setpoint_s _rover_throttle_setpoint{}; // uORB publications - uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; - uORB::Publication _actuator_servos_pub{ORB_ID(actuator_servos)}; uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; // Class instances + AckermannActControl _ackermann_act_control{this}; AckermannRateControl _ackermann_rate_control{this}; AckermannAttControl _ackermann_att_control{this}; AckermannVelControl _ackermann_vel_control{this}; AckermannPosControl _ackermann_pos_control{this}; - // Variables - hrt_abstime _timestamp{0}; - float _dt{0.f}; - float _current_servo_setpoint{0.f}; - float _current_motor_setpoint{0.f}; - - // Controllers - SlewRate _servo_setpoint{0.f}; - SlewRate _motor_setpoint{0.f}; - - // Parameters - DEFINE_PARAMETERS( - (ParamInt) _param_r_rev, - (ParamFloat) _param_ra_str_rate_limit, - (ParamFloat) _param_ra_max_str_ang, - (ParamFloat) _param_ro_accel_limit, - (ParamFloat) _param_ro_decel_limit, - (ParamFloat) _param_ro_max_thr_speed - ) }; From cd486b2da65a9f31a1d7f3135288815aad483199 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Wed, 30 Apr 2025 08:44:43 +0200 Subject: [PATCH 045/130] ackermann: update position control --- msg/RoverPositionSetpoint.msg | 6 +- .../AckermannPosControl.cpp | 228 ++++++++---------- .../AckermannPosControl.hpp | 78 +++--- 3 files changed, 149 insertions(+), 163 deletions(-) diff --git a/msg/RoverPositionSetpoint.msg b/msg/RoverPositionSetpoint.msg index 282eebfd51..d2ac0ac088 100644 --- a/msg/RoverPositionSetpoint.msg +++ b/msg/RoverPositionSetpoint.msg @@ -1,6 +1,8 @@ uint64 timestamp # time since system start (microseconds) float32[2] position_ned # 2-dimensional position setpoint in NED frame [m] -float32 cruising_speed # (Optional) Specify rover speed (Defaults to maximum speed) +float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position) +float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed) +float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero) -float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. +float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw) diff --git a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp index 077760b8c4..681d775699 100644 --- a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp +++ b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp @@ -41,10 +41,6 @@ AckermannPosControl::AckermannPosControl(ModuleParams *parent) : ModuleParams(pa _rover_position_setpoint_pub.advertise(); _rover_velocity_setpoint_pub.advertise(); - // Initially set to NaN to indicate that the rover has no position setpoint - _rover_position_setpoint.position_ned[0] = NAN; - _rover_position_setpoint.position_ned[1] = NAN; - updateParams(); } @@ -61,21 +57,24 @@ void AckermannPosControl::updateParams() void AckermannPosControl::updatePosControl() { - const hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - updateSubscriptions(); if (_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { + // Generate Position Setpoint if (_vehicle_control_mode.flag_control_offboard_enabled) { generatePositionSetpoint(); + + } else if (_vehicle_control_mode.flag_control_manual_enabled) { + manualPositionMode(); + + } else if (_vehicle_control_mode.flag_control_auto_enabled) { + autoPositionMode(); } + // Generate Velocity Setpoint generateVelocitySetpoint(); } - } void AckermannPosControl::updateSubscriptions() @@ -121,7 +120,7 @@ void AckermannPosControl::generatePositionSetpoint() // Translate trajectory setpoint to rover position setpoint rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = _timestamp; + rover_position_setpoint.timestamp = hrt_absolute_time(); rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; rover_position_setpoint.cruising_speed = _param_ro_speed_limit.get(); @@ -130,31 +129,10 @@ void AckermannPosControl::generatePositionSetpoint() } -void AckermannPosControl::generateVelocitySetpoint() -{ - // Manual Position Mode - if (_vehicle_control_mode.flag_control_manual_enabled && _vehicle_control_mode.flag_control_position_enabled) { - manualPositionMode(); - return; - } - - // Auto Mode - if (_vehicle_control_mode.flag_control_auto_enabled) { - autoPositionMode(); - return; - } - - // Rover Position Setpoint - if (_rover_position_setpoint_sub.copy(&_rover_position_setpoint) - && PX4_ISFINITE(_rover_position_setpoint.position_ned[0]) && PX4_ISFINITE(_rover_position_setpoint.position_ned[1])) { - goToPositionMode(); - return; - } - -} - void AckermannPosControl::manualPositionMode() { + updateSubscriptions(); + manual_control_setpoint_s manual_control_setpoint{}; _manual_control_setpoint_sub.copy(&manual_control_setpoint); @@ -167,12 +145,21 @@ void AckermannPosControl::manualPositionMode() if (fabsf(yaw_delta) > FLT_EPSILON || fabsf(speed_setpoint) < FLT_EPSILON) { // Closed loop yaw rate control _course_control = false; + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + sign(speed_setpoint) * yaw_delta); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = yaw_setpoint; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); + const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * + pos_ctl_course_direction; + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); } else { // Course control if the steering input is zero (keep driving on a straight line) if (!_course_control) { @@ -186,24 +173,23 @@ void AckermannPosControl::manualPositionMode() const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * vector_scaling * _pos_ctl_course_direction; - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = _timestamp; - const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _pos_ctl_start_position_ned, - _curr_pos_ned, fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi( - bearing_setpoint + M_PI_F); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); + rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); } } void AckermannPosControl::autoPositionMode() { + updateSubscriptions(); + if (_position_setpoint_triplet_sub.updated()) { updateWaypointsAndAcceptanceRadius(); } @@ -214,40 +200,19 @@ void AckermannPosControl::autoPositionMode() const float distance_to_curr_wp = sqrt(powf(_curr_pos_ned(0) - _curr_wp_ned(0), 2) + powf(_curr_pos_ned(1) - _curr_wp_ned(1), 2)); - // Check stopping conditions - bool auto_stop{false}; - - if (_curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND - || _curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE - || !_next_wp_ned.isAllFinite()) { - auto_stop = distance_to_curr_wp < _param_nav_acc_rad.get(); - } - - if (auto_stop) { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = 0.f; - rover_velocity_setpoint.bearing = _vehicle_yaw; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } else { // Regular guidance algorithm - const float speed_setpoint = calcSpeedSetpoint(_cruising_speed, _min_speed, distance_to_prev_wp, - distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _param_ro_decel_limit.get(), - _param_ro_jerk_limit.get(), _curr_wp_type, _waypoint_transition_angle, _prev_waypoint_transition_angle, - _param_ro_speed_limit.get()); - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = _timestamp; - const float yaw_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), _curr_wp_ned, _prev_wp_ned, _curr_pos_ned, - fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = yaw_setpoint; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = _curr_wp_ned(0); + rover_position_setpoint.position_ned[1] = _curr_wp_ned(1); + rover_position_setpoint.start_ned[0] = _prev_wp_ned(0); + rover_position_setpoint.start_ned[1] = _prev_wp_ned(1); + rover_position_setpoint.arrival_speed = autoArrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius, _curr_wp_type, + _waypoint_transition_angle, _max_yaw_rate); + rover_position_setpoint.cruising_speed = autoCruisingSpeed(_cruising_speed, _min_speed, distance_to_prev_wp, + distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _waypoint_transition_angle, + _prev_waypoint_transition_angle, _max_yaw_rate); + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); } void AckermannPosControl::updateWaypointsAndAcceptanceRadius() @@ -298,87 +263,104 @@ float AckermannPosControl::updateAcceptanceRadius(const float waypoint_transitio // Publish updated acceptance radius position_controller_status_s pos_ctrl_status{}; pos_ctrl_status.acceptance_radius = acceptance_radius; - pos_ctrl_status.timestamp = _timestamp; + pos_ctrl_status.timestamp = hrt_absolute_time(); _position_controller_status_pub.publish(pos_ctrl_status); return acceptance_radius; } -float AckermannPosControl::calcSpeedSetpoint(const float cruising_speed, const float miss_speed_min, - const float distance_to_prev_wp, const float distance_to_curr_wp, const float acc_rad, - const float prev_acc_rad, const float max_decel, const float max_jerk, const int curr_wp_type, - const float waypoint_transition_angle, const float prev_waypoint_transition_angle, const float max_speed) +float AckermannPosControl::autoArrivalSpeed(const float cruising_speed, const float miss_speed_min, const float acc_rad, + const int curr_wp_type, const float waypoint_transition_angle, const float max_yaw_rate) +{ + if (!PX4_ISFINITE(waypoint_transition_angle) + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { + return 0.f; // Stop at the waypoint + + } else { + const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); + const float cornering_speed = max_yaw_rate * turning_circle; + return math::constrain(cornering_speed, miss_speed_min, cruising_speed); // Slow down for cornering + } +} + +float AckermannPosControl::autoCruisingSpeed(const float cruising_speed, const float miss_speed_min, + const float distance_to_prev_wp, const float distance_to_curr_wp, const float acc_rad, const float prev_acc_rad, + const float waypoint_transition_angle, const float prev_waypoint_transition_angle, const float max_yaw_rate) { // Catch improper values if (miss_speed_min < -FLT_EPSILON || miss_speed_min > cruising_speed) { return cruising_speed; } - // Upcoming stop - if (max_decel > FLT_EPSILON && max_jerk > FLT_EPSILON && (!PX4_ISFINITE(waypoint_transition_angle) - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE)) { - const float straight_line_speed = math::trajectory::computeMaxSpeedFromDistance(max_jerk, - max_decel, distance_to_curr_wp, 0.f); - return math::min(straight_line_speed, cruising_speed); - } - // Cornering slow down effect if (distance_to_prev_wp <= prev_acc_rad && prev_acc_rad > FLT_EPSILON && PX4_ISFINITE(prev_waypoint_transition_angle)) { const float turning_circle = prev_acc_rad * tanf(prev_waypoint_transition_angle / 2.f); - const float cornering_speed = _max_yaw_rate * turning_circle; + const float cornering_speed = max_yaw_rate * turning_circle; return math::constrain(cornering_speed, miss_speed_min, cruising_speed); } if (distance_to_curr_wp <= acc_rad && acc_rad > FLT_EPSILON && PX4_ISFINITE(waypoint_transition_angle)) { const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); - const float cornering_speed = _max_yaw_rate * turning_circle; + const float cornering_speed = max_yaw_rate * turning_circle; return math::constrain(cornering_speed, miss_speed_min, cruising_speed); } - // Straight line speed - if (max_decel > FLT_EPSILON && max_jerk > FLT_EPSILON && acc_rad > FLT_EPSILON) { - const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); - float cornering_speed = _max_yaw_rate * turning_circle; - cornering_speed = math::constrain(cornering_speed, miss_speed_min, cruising_speed); - const float straight_line_speed = math::trajectory::computeMaxSpeedFromDistance(max_jerk, - max_decel, distance_to_curr_wp - acc_rad, cornering_speed); - return math::min(straight_line_speed, cruising_speed); - - } - return cruising_speed; // Fallthrough } -void AckermannPosControl::goToPositionMode() +void AckermannPosControl::generateVelocitySetpoint() { + hrt_abstime timestamp = hrt_absolute_time(); + + if (_rover_position_setpoint_sub.updated()) { + _rover_position_setpoint_sub.copy(&_rover_position_setpoint); + _start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]); + _start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned; + } + + if (_position_controller_status_sub.updated()) { + position_controller_status_s position_controller_status{}; + _position_controller_status_sub.copy(&position_controller_status); + _acceptance_radius = position_controller_status.acceptance_radius; + } + const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]); const float distance_to_target = (target_waypoint_ned - _curr_pos_ned).norm(); if (distance_to_target > _param_nav_acc_rad.get()) { + + float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : + 0.f; + const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _acceptance_radius : distance_to_target; float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), - _param_ro_decel_limit.get(), distance_to_target, 0.f); - const float max_speed = PX4_ISFINITE(_rover_position_setpoint.cruising_speed) ? - _rover_position_setpoint.cruising_speed : - _param_ro_speed_limit.get(); - speed_setpoint = math::min(speed_setpoint, max_speed); + _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); + speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); + + if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { + speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, + fabsf(_rover_position_setpoint.cruising_speed)); + } + pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = _timestamp; + pure_pursuit_status.timestamp = timestamp; + const float yaw_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _curr_pos_ned, + _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, _curr_pos_ned, fabsf(speed_setpoint)); _pure_pursuit_status_pub.publish(pure_pursuit_status); rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; + rover_velocity_setpoint.timestamp = timestamp; rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = yaw_setpoint; + rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? yaw_setpoint : matrix::wrap_pi( + yaw_setpoint + M_PI_F); _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); } else { rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; + rover_velocity_setpoint.timestamp = timestamp; rover_velocity_setpoint.speed = 0.f; rover_velocity_setpoint.bearing = _vehicle_yaw; _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); diff --git a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp index 8f9e37eb65..fab6c96e30 100644 --- a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp +++ b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp @@ -78,10 +78,20 @@ public: ~AckermannPosControl() = default; /** - * @brief Update position controller. + * @brief Update position control */ void updatePosControl(); + /** + * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint. + */ + void manualPositionMode(); + + /** + * @brief Generate and publish roverVelocitySetpoint from positionSetpointTriplet. + */ + void autoPositionMode(); + protected: /** * @brief Update the parameters of the module. @@ -99,27 +109,6 @@ private: */ void generatePositionSetpoint(); - /** - * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint (Position Mode) or - * positionSetpointTriplet (Auto Mode) or roverPositionSetpoint. - */ - void generateVelocitySetpoint(); - - /** - * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint. - */ - void manualPositionMode(); - - /** - * @brief Generate and publish roverVelocitySetpoint from positionSetpointTriplet. - */ - void autoPositionMode(); - - /** - * @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint. - */ - void goToPositionMode(); - /** * @brief Update global/NED waypoint coordinates and acceptance radius. */ @@ -140,26 +129,34 @@ private: float acceptance_radius_gain, float acceptance_radius_max, float wheel_base, float max_steer_angle); /** - * @brief Calculate the speed setpoint. During cornering the speed is restricted based on the radius of the corner. - * On straight lines it is based on a speed trajectory such that the rover will arrive at the next corner with the - * desired cornering speed under consideration of the maximum deceleration and jerk. + * @brief Calculate the speed at which the rover should arrive at the current waypoint based on the upcoming corner. * @param cruising_speed Cruising speed [m/s]. * @param miss_speed_min Minimum speed setpoint [m/s]. - * @param distance_to_prev_wp Distance to the previous waypoint [m]. - * @param distance_to_curr_wp Distance to the current waypoint [m]. * @param acc_rad Acceptance radius of the current waypoint [m]. - * @param prev_acc_rad Acceptance radius of the previous waypoint [m]. - * @param max_decel Maximum allowed deceleration [m/s^2]. - * @param max_jerk Maximum allowed jerk [m/s^3]. * @param curr_wp_type Type of the current waypoint. * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param prev_waypoint_transition_angle Previous angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param max_speed Maximum speed setpoint [m/s] + * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] * @return Speed setpoint [m/s]. */ - float calcSpeedSetpoint(float cruising_speed, float miss_speed_min, float distance_to_prev_wp, - float distance_to_curr_wp, float acc_rad, float prev_acc_rad, float max_decel, float max_jerk, int curr_wp_type, - float waypoint_transition_angle, float prev_waypoint_transition_angle, float max_speed); + float autoArrivalSpeed(float cruising_speed, float miss_speed_min, float acc_rad, int curr_wp_type, + float waypoint_transition_angle, float max_yaw_rate); + + /** + * @brief Calculate the cruising speed setpoint. During cornering the speed is restricted based on the radius of the corner. + * @param cruising_speed Cruising speed [m/s]. + * @param miss_speed_min Minimum speed setpoint [m/s]. + * @param distance_to_prev_wp Distance to the previous waypoint [m]. + * @param distance_to_curr_wp Distance to the current waypoint [m]. + * @param acc_rad Acceptance radius of the current waypoint [m]. + * @param prev_acc_rad Acceptance radius of the previous waypoint [m]. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param prev_waypoint_transition_angle Previous angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] + * @return Speed setpoint [m/s]. + */ + float autoCruisingSpeed(float cruising_speed, float miss_speed_min, float distance_to_prev_wp, + float distance_to_curr_wp, float acc_rad, float prev_acc_rad, float waypoint_transition_angle, + float prev_waypoint_transition_angle, float max_yaw_rate); /** * @brief Check if the necessary parameters are set. @@ -167,6 +164,11 @@ private: */ bool runSanityChecks(); + /** + * @brief Generate RoverVelocitySetpoint from RoverPositionSetpoint + */ + void generateVelocitySetpoint(); + // uORB subscriptions uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; @@ -176,9 +178,10 @@ private: uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _rover_position_setpoint_sub{ORB_ID(rover_position_setpoint)}; + uORB::Subscription _position_controller_status_sub{ORB_ID(position_controller_status)}; + rover_position_setpoint_s _rover_position_setpoint{}; vehicle_control_mode_s _vehicle_control_mode{}; offboard_control_mode_s _offboard_control_mode{}; - rover_position_setpoint_s _rover_position_setpoint{}; // uORB publications uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; @@ -187,15 +190,14 @@ private: uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; // Variables - hrt_abstime _timestamp{0}; Quatf _vehicle_attitude_quaternion{}; Vector2f _curr_pos_ned{}; Vector2f _pos_ctl_course_direction{}; Vector2f _pos_ctl_start_position_ned{}; + Vector2f _start_ned{}; float _vehicle_yaw{0.f}; float _max_yaw_rate{0.f}; float _min_speed{0.f}; // Speed at which the maximum yaw rate limit is enforced given the maximum steer angle and wheel base. - float _dt{0.f}; int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE}; bool _course_control{false}; // Indicates if the rover is doing course control in manual position mode. bool _prev_param_check_passed{true}; From 47a9b552f81a7b0fbfbfe4261e241ab1938e97e2 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Wed, 30 Apr 2025 09:10:01 +0200 Subject: [PATCH 046/130] ackermann: centralize mode management, resets and checks --- .../AckermannActControl.cpp | 100 ++-- .../AckermannActControl.hpp | 30 +- .../AckermannAttControl.cpp | 139 ++---- .../AckermannAttControl.hpp | 48 +- .../AckermannPosControl.cpp | 340 ++----------- .../AckermannPosControl.hpp | 131 +---- .../AckermannRateControl.cpp | 204 +++----- .../AckermannRateControl.hpp | 47 +- .../AckermannVelControl.cpp | 120 ++--- .../AckermannVelControl.hpp | 47 +- .../rover_ackermann/RoverAckermann.cpp | 469 +++++++++++++++++- .../rover_ackermann/RoverAckermann.hpp | 178 ++++++- 12 files changed, 961 insertions(+), 892 deletions(-) diff --git a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp index c898186ec7..4022464167 100644 --- a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp +++ b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp @@ -57,49 +57,83 @@ void AckermannActControl::updateActControl() { const hrt_abstime timestamp_prev = _timestamp; _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + + // Motor control + if (_rover_throttle_setpoint_sub.updated()) { + rover_throttle_setpoint_s rover_throttle_setpoint{}; + _rover_throttle_setpoint_sub.copy(&rover_throttle_setpoint); + _throttle_setpoint = rover_throttle_setpoint.throttle_body_x; + } + + if (PX4_ISFINITE(_throttle_setpoint)) { + actuator_motors_s actuator_motors_sub{}; + _actuator_motors_sub.copy(&actuator_motors_sub); + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + actuator_motors.control[0] = RoverControl::throttleControl(_motor_setpoint, + _throttle_setpoint, actuator_motors_sub.control[0], _param_ro_accel_limit.get(), + _param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), dt); + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + + } else { + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + actuator_motors.control[0] = 0.f; + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + } + + // Servo control + if (_rover_steering_setpoint_sub.updated()) { + rover_steering_setpoint_s rover_steering_setpoint{}; + _rover_steering_setpoint_sub.copy(&rover_steering_setpoint); + _steering_setpoint = rover_steering_setpoint.normalized_steering_angle; + } + + if (PX4_ISFINITE(_steering_setpoint)) { + actuator_servos_s actuator_servos_sub{}; + _actuator_servos_sub.copy(&actuator_servos_sub); + + if (_param_ra_str_rate_limit.get() > FLT_EPSILON + && _param_ra_max_str_ang.get() > FLT_EPSILON) { // Apply slew rate if configured + if (fabsf(_servo_setpoint.getState() - actuator_servos_sub.control[0]) > fabsf( + _steering_setpoint - + actuator_servos_sub.control[0])) { + _servo_setpoint.setForcedValue(actuator_servos_sub.control[0]); + } + + _servo_setpoint.update(_steering_setpoint, dt); + + } else { + _servo_setpoint.setForcedValue(_steering_setpoint); + } + + actuator_servos_s actuator_servos{}; + actuator_servos.control[0] = _servo_setpoint.getState(); + actuator_servos.timestamp = _timestamp; + _actuator_servos_pub.publish(actuator_servos); + + } else { + actuator_servos_s actuator_servos{}; + actuator_servos.control[0] = 0.f; + actuator_servos.timestamp = _timestamp; + _actuator_servos_pub.publish(actuator_servos); + } - generateActuatorSetpoint(); } -void AckermannActControl::generateActuatorSetpoint() +void AckermannActControl::stopVehicle() { - // Motor control - rover_throttle_setpoint_s rover_throttle_setpoint{}; - _rover_throttle_setpoint_sub.copy(&rover_throttle_setpoint); - actuator_motors_s actuator_motors_sub{}; - _actuator_motors_sub.copy(&actuator_motors_sub); actuator_motors_s actuator_motors{}; actuator_motors.reversible_flags = _param_r_rev.get(); - actuator_motors.control[0] = RoverControl::throttleControl(_motor_setpoint, - rover_throttle_setpoint.throttle_body_x, actuator_motors_sub.control[0], _param_ro_accel_limit.get(), - _param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), _dt); + actuator_motors.control[0] = 0.f; actuator_motors.timestamp = _timestamp; _actuator_motors_pub.publish(actuator_motors); - - // Servo control - rover_steering_setpoint_s rover_steering_setpoint{}; - _rover_steering_setpoint_sub.copy(&rover_steering_setpoint); - actuator_servos_s actuator_servos_sub{}; - _actuator_servos_sub.copy(&actuator_servos_sub); - - if (_param_ra_str_rate_limit.get() > FLT_EPSILON - && _param_ra_max_str_ang.get() > FLT_EPSILON) { // Apply slew rate if configured - if (fabsf(_servo_setpoint.getState() - actuator_servos_sub.control[0]) > fabsf( - rover_steering_setpoint.normalized_steering_angle - - actuator_servos_sub.control[0])) { - _servo_setpoint.setForcedValue(actuator_servos_sub.control[0]); - } - - _servo_setpoint.update(rover_steering_setpoint.normalized_steering_angle, _dt); - - } else { - _servo_setpoint.setForcedValue(rover_steering_setpoint.normalized_steering_angle); - } - actuator_servos_s actuator_servos{}; - actuator_servos.control[0] = _servo_setpoint.getState(); + actuator_servos.control[0] = 0.f; actuator_servos.timestamp = _timestamp; _actuator_servos_pub.publish(actuator_servos); } diff --git a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp index d8933525e3..fb3630c13c 100644 --- a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp +++ b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.hpp @@ -44,7 +44,6 @@ // uORB includes #include #include -#include #include #include #include @@ -64,10 +63,15 @@ public: ~AckermannActControl() = default; /** - * @brief Update actuator controller. + * @brief Generate and publish actuatorMotors/actuatorServos setpoints from roverThrottleSetpoint/roverSteeringSetpoint. */ void updateActControl(); + /** + * @brief Stop the vehicle by sending 0 commands to motors and servos. + */ + void stopVehicle(); + protected: /** * @brief Update the parameters of the module. @@ -76,11 +80,6 @@ protected: private: - /** - * @brief Generate and publish actuatorMotors/actuatorServos setpoints from roverThrottleSetpoint/roverSteeringSetpoint. - */ - void generateActuatorSetpoint(); - // uORB subscriptions uORB::Subscription _actuator_servos_sub{ORB_ID(actuator_servos)}; uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; @@ -88,12 +87,13 @@ private: uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)}; // uORB publications - uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; - uORB::Publication _actuator_servos_pub{ORB_ID(actuator_servos)}; + uORB::Publication _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _actuator_servos_pub{ORB_ID(actuator_servos)}; // Variables hrt_abstime _timestamp{0}; - float _dt{0.f}; + float _throttle_setpoint{NAN}; + float _steering_setpoint{NAN}; // Controllers SlewRate _servo_setpoint{0.f}; @@ -101,11 +101,11 @@ private: // Parameters DEFINE_PARAMETERS( - (ParamInt) _param_r_rev, - (ParamFloat) _param_ra_str_rate_limit, - (ParamFloat) _param_ra_max_str_ang, - (ParamFloat) _param_ro_accel_limit, - (ParamFloat) _param_ro_decel_limit, + (ParamInt) _param_r_rev, + (ParamFloat) _param_ra_str_rate_limit, + (ParamFloat) _param_ra_max_str_ang, + (ParamFloat) _param_ro_accel_limit, + (ParamFloat) _param_ro_decel_limit, (ParamFloat) _param_ro_max_thr_speed ) }; diff --git a/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp b/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp index 9c07a3ab3b..a866390316 100644 --- a/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp +++ b/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp @@ -38,8 +38,6 @@ using namespace time_literals; AckermannAttControl::AckermannAttControl(ModuleParams *parent) : ModuleParams(parent) { _rover_rate_setpoint_pub.advertise(); - _rover_throttle_setpoint_pub.advertise(); - _rover_attitude_setpoint_pub.advertise(); _rover_attitude_status_pub.advertise(); updateParams(); } @@ -52,47 +50,42 @@ void AckermannAttControl::updateParams() _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; } + // Set up PID controller _pid_yaw.setGains(_param_ro_yaw_p.get(), 0.f, 0.f); _pid_yaw.setIntegralLimit(0.f); _pid_yaw.setOutputLimit(_max_yaw_rate); + + // Set up slew rate _adjusted_yaw_setpoint.setSlewRate(_max_yaw_rate); } void AckermannAttControl::updateAttControl() { + updateSubscriptions(); + hrt_abstime timestamp_prev = _timestamp; _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); - } + if (PX4_ISFINITE(_yaw_setpoint)) { + // Calculate yaw rate limit for slew rate + float max_possible_yaw_rate = fabsf(_estimated_speed_body_x) * tanf(_param_ra_max_str_ang.get()) / + _param_ra_wheel_base.get(); // Maximum possible yaw rate at current velocity + float yaw_slew_rate = math::min(max_possible_yaw_rate, _max_yaw_rate); - if (_vehicle_attitude_sub.updated()) { - vehicle_attitude_s vehicle_attitude{}; - _vehicle_attitude_sub.copy(&vehicle_attitude); - matrix::Quatf vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); - _vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); - } + float yaw_rate_setpoint = RoverControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, yaw_slew_rate, + _vehicle_yaw, _yaw_setpoint, dt); - if (_vehicle_control_mode.flag_control_attitude_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { - // Estimate forward speed based on throttle - if (_actuator_motors_sub.updated()) { - actuator_motors_s actuator_motors; - _actuator_motors_sub.copy(&actuator_motors); - _estimated_speed_body_x = math::interpolate (actuator_motors.control[0], -1.f, 1.f, - -_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get()); - } + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = _timestamp; + rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate); + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); - if (_vehicle_control_mode.flag_control_manual_enabled) { - generateAttitudeAndThrottleSetpoint(); - } - - generateRateSetpoint(); - - } else { // Reset pid and slew rate when attitude control is not active - _pid_yaw.resetIntegral(); - _adjusted_yaw_setpoint.setForcedValue(0.f); + } else { + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = _timestamp; + rover_rate_setpoint.yaw_rate_setpoint = 0.f; + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); } // Publish attitude controller status (logging only) @@ -104,82 +97,28 @@ void AckermannAttControl::updateAttControl() } -void AckermannAttControl::generateAttitudeAndThrottleSetpoint() +void AckermannAttControl::updateSubscriptions() { - const bool stab_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled - && !_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_control_attitude_enabled; - - if (stab_mode_enabled && _manual_control_setpoint_sub.updated()) { // Stab Mode - manual_control_setpoint_s manual_control_setpoint{}; - - if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - - const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), - _max_yaw_rate / _param_ro_yaw_p.get()); - - if (fabsf(yaw_delta) > FLT_EPSILON - || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { // Closed loop yaw rate control - _stab_yaw_ctl = false; - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + matrix::sign(manual_control_setpoint.throttle) * yaw_delta); - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = yaw_setpoint; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - - } else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw) - if (!_stab_yaw_ctl) { - _stab_yaw_setpoint = _vehicle_yaw; - _stab_yaw_ctl = true; - } - - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } - - - } - + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + matrix::Quatf vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); + } + + // Estimate forward speed based on throttle + if (_actuator_motors_sub.updated()) { + actuator_motors_s actuator_motors; + _actuator_motors_sub.copy(&actuator_motors); + _estimated_speed_body_x = math::interpolate (actuator_motors.control[0], -1.f, 1.f, + -_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get()); } -} -void AckermannAttControl::generateRateSetpoint() -{ if (_rover_attitude_setpoint_sub.updated()) { - _rover_attitude_setpoint_sub.copy(&_rover_attitude_setpoint); + rover_attitude_setpoint_s rover_attitude_setpoint{}; + _rover_attitude_setpoint_sub.copy(&rover_attitude_setpoint); + _yaw_setpoint = rover_attitude_setpoint.yaw_setpoint; } - - if (_rover_rate_setpoint_sub.updated()) { - _rover_rate_setpoint_sub.copy(&_rover_rate_setpoint); - } - - // Check if a new rate setpoint was already published from somewhere else - if (_rover_rate_setpoint.timestamp > _last_rate_setpoint_update - && _rover_rate_setpoint.timestamp > _rover_attitude_setpoint.timestamp) { - return; - } - - // Calculate yaw rate limit for slew rate - float max_possible_yaw_rate = fabsf(_estimated_speed_body_x) * tanf(_param_ra_max_str_ang.get()) / - _param_ra_wheel_base.get(); // Maximum possible yaw rate at current velocity - float yaw_slew_rate = math::min(max_possible_yaw_rate, _max_yaw_rate); - - float yaw_rate_setpoint = RoverControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, yaw_slew_rate, - _vehicle_yaw, _rover_attitude_setpoint.yaw_setpoint, _dt); - - _last_rate_setpoint_update = _timestamp; - rover_rate_setpoint_s rover_rate_setpoint{}; - rover_rate_setpoint.timestamp = _timestamp; - rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate); - _rover_rate_setpoint_pub.publish(rover_rate_setpoint); } bool AckermannAttControl::runSanityChecks() diff --git a/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.hpp b/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.hpp index 93d17928be..2d58bae4ce 100644 --- a/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.hpp +++ b/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.hpp @@ -47,9 +47,6 @@ #include #include #include -#include -#include -#include #include #include #include @@ -69,10 +66,21 @@ public: ~AckermannAttControl() = default; /** - * @brief Update attitude controller. + * @brief Generate and publish roverRateSetpoint from roverAttitudeSetpoint. */ void updateAttControl(); + /** + * @brief Reset attitude controller. + */ + void reset() {_pid_yaw.resetIntegral(); _yaw_setpoint = NAN;}; + + /** + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. + */ + bool runSanityChecks(); + protected: /** * @brief Update the parameters of the module. @@ -81,48 +89,26 @@ protected: private: /** - * @brief Generate and publish roverAttitudeSetpoint and roverThrottleSetpoint from manualControlSetpoint (Stab Mode). + * @brief Update uORB subscriptions used in attitude controller. */ - void generateAttitudeAndThrottleSetpoint(); - - /** - * @brief Generate and publish roverRateSetpoint from roverAttitudeSetpoint. - */ - void generateRateSetpoint(); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); + void updateSubscriptions(); // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; uORB::Subscription _rover_attitude_setpoint_sub{ORB_ID(rover_attitude_setpoint)}; - uORB::Subscription _rover_rate_setpoint_sub{ORB_ID(rover_rate_setpoint)}; - vehicle_control_mode_s _vehicle_control_mode{}; - rover_attitude_setpoint_s _rover_attitude_setpoint{}; - rover_rate_setpoint_s _rover_rate_setpoint{}; // uORB publications - uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; - uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; - uORB::Publication _rover_attitude_status_pub{ORB_ID(rover_attitude_status)}; + uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; + uORB::Publication _rover_attitude_status_pub{ORB_ID(rover_attitude_status)}; // Variables float _vehicle_yaw{0.f}; hrt_abstime _timestamp{0}; - hrt_abstime _last_rate_setpoint_update{0}; - float _dt{0.f}; float _max_yaw_rate{0.f}; float _estimated_speed_body_x{0.f}; /*Vehicle speed estimated by interpolating [actuatorMotorSetpoint, _estimated_speed_body_x] between [0, 0] and [1, _param_ro_max_thr_speed].*/ - float _stab_yaw_setpoint{0.f}; // Yaw setpoint if rover is doing yaw control in stab mode - bool _stab_yaw_ctl{false}; // Indicates if rover is doing yaw control in stab mode + float _yaw_setpoint{NAN}; // Controllers PID _pid_yaw; diff --git a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp index 681d775699..a2b5ec0e01 100644 --- a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp +++ b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp @@ -38,7 +38,6 @@ using namespace time_literals; AckermannPosControl::AckermannPosControl(ModuleParams *parent) : ModuleParams(parent) { _pure_pursuit_status_pub.advertise(); - _rover_position_setpoint_pub.advertise(); _rover_velocity_setpoint_pub.advertise(); updateParams(); @@ -49,38 +48,66 @@ void AckermannPosControl::updateParams() ModuleParams::updateParams(); _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; - if (_param_ra_wheel_base.get() > FLT_EPSILON && _max_yaw_rate > FLT_EPSILON - && _param_ra_max_str_ang.get() > FLT_EPSILON) { - _min_speed = _param_ra_wheel_base.get() * _max_yaw_rate / tanf(_param_ra_max_str_ang.get()); - } } void AckermannPosControl::updatePosControl() { updateSubscriptions(); - if (_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { - // Generate Position Setpoint - if (_vehicle_control_mode.flag_control_offboard_enabled) { - generatePositionSetpoint(); + hrt_abstime timestamp = hrt_absolute_time(); - } else if (_vehicle_control_mode.flag_control_manual_enabled) { - manualPositionMode(); + const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]); + float distance_to_target = target_waypoint_ned.isAllFinite() ? (target_waypoint_ned - _curr_pos_ned).norm() : NAN; - } else if (_vehicle_control_mode.flag_control_auto_enabled) { - autoPositionMode(); + if (PX4_ISFINITE(distance_to_target) && distance_to_target > _acceptance_radius) { + + float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : + 0.f; + const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _acceptance_radius : distance_to_target; + float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), + _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); + speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); + + if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { + speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, + fabsf(_rover_position_setpoint.cruising_speed)); } - // Generate Velocity Setpoint - generateVelocitySetpoint(); + pure_pursuit_status_s pure_pursuit_status{}; + pure_pursuit_status.timestamp = timestamp; + const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), + _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, + _curr_pos_ned, fabsf(speed_setpoint)); + _pure_pursuit_status_pub.publish(pure_pursuit_status); + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = timestamp; + rover_velocity_setpoint.speed = speed_setpoint; + rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi( + bearing_setpoint + M_PI_F); + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + } else { + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = timestamp; + rover_velocity_setpoint.speed = 0.f; + rover_velocity_setpoint.bearing = _vehicle_yaw; + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); } } void AckermannPosControl::updateSubscriptions() { - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); + if (_rover_position_setpoint_sub.updated()) { + _rover_position_setpoint_sub.copy(&_rover_position_setpoint); + _start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]); + _start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned; + } + + if (_position_controller_status_sub.updated()) { + position_controller_status_s position_controller_status{}; + _position_controller_status_sub.copy(&position_controller_status); + _acceptance_radius = position_controller_status.acceptance_radius; } if (_vehicle_attitude_sub.updated()) { @@ -105,292 +132,13 @@ void AckermannPosControl::updateSubscriptions() } -void AckermannPosControl::generatePositionSetpoint() -{ - if (_offboard_control_mode_sub.updated()) { - _offboard_control_mode_sub.copy(&_offboard_control_mode); - } - - if (!_offboard_control_mode.position) { - return; - } - - trajectory_setpoint_s trajectory_setpoint{}; - _trajectory_setpoint_sub.copy(&trajectory_setpoint); - - // Translate trajectory setpoint to rover position setpoint - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; - rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; - rover_position_setpoint.cruising_speed = _param_ro_speed_limit.get(); - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - -} - -void AckermannPosControl::manualPositionMode() -{ - updateSubscriptions(); - - manual_control_setpoint_s manual_control_setpoint{}; - _manual_control_setpoint_sub.copy(&manual_control_setpoint); - - const float speed_setpoint = math::interpolate(manual_control_setpoint.throttle, - -1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); - const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), - _max_yaw_rate / _param_ro_yaw_p.get()); - - if (fabsf(yaw_delta) > FLT_EPSILON - || fabsf(speed_setpoint) < FLT_EPSILON) { // Closed loop yaw rate control - _course_control = false; - // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + sign(speed_setpoint) * yaw_delta); - const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); - const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * - pos_ctl_course_direction; - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); - rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); - rover_position_setpoint.start_ned[0] = NAN; - rover_position_setpoint.start_ned[1] = NAN; - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.cruising_speed = speed_setpoint; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - - } else { // Course control if the steering input is zero (keep driving on a straight line) - if (!_course_control) { - _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); - _pos_ctl_start_position_ned = _curr_pos_ned; - _course_control = true; - } - - // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover - const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned; - const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); - const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * - vector_scaling * _pos_ctl_course_direction; - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); - rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); - rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); - rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.cruising_speed = speed_setpoint; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - } -} - -void AckermannPosControl::autoPositionMode() -{ - updateSubscriptions(); - - if (_position_setpoint_triplet_sub.updated()) { - updateWaypointsAndAcceptanceRadius(); - } - - // Distances to waypoints - const float distance_to_prev_wp = sqrt(powf(_curr_pos_ned(0) - _prev_wp_ned(0), - 2) + powf(_curr_pos_ned(1) - _prev_wp_ned(1), 2)); - const float distance_to_curr_wp = sqrt(powf(_curr_pos_ned(0) - _curr_wp_ned(0), - 2) + powf(_curr_pos_ned(1) - _curr_wp_ned(1), 2)); - - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = _curr_wp_ned(0); - rover_position_setpoint.position_ned[1] = _curr_wp_ned(1); - rover_position_setpoint.start_ned[0] = _prev_wp_ned(0); - rover_position_setpoint.start_ned[1] = _prev_wp_ned(1); - rover_position_setpoint.arrival_speed = autoArrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius, _curr_wp_type, - _waypoint_transition_angle, _max_yaw_rate); - rover_position_setpoint.cruising_speed = autoCruisingSpeed(_cruising_speed, _min_speed, distance_to_prev_wp, - distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _waypoint_transition_angle, - _prev_waypoint_transition_angle, _max_yaw_rate); - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); -} - -void AckermannPosControl::updateWaypointsAndAcceptanceRadius() -{ - position_setpoint_triplet_s position_setpoint_triplet{}; - _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); - _curr_wp_type = position_setpoint_triplet.current.type; - - RoverControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet, - _curr_pos_ned, _global_ned_proj_ref); - - _prev_waypoint_transition_angle = _waypoint_transition_angle; - _waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned, _next_wp_ned); - - // Update acceptance radius - _prev_acceptance_radius = _acceptance_radius; - - if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) { - _acceptance_radius = updateAcceptanceRadius(_waypoint_transition_angle, _param_nav_acc_rad.get(), - _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_str_ang.get()); - - } else { - _acceptance_radius = _param_nav_acc_rad.get(); - } - - // Waypoint cruising speed - _cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain( - position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get(); -} - -float AckermannPosControl::updateAcceptanceRadius(const float waypoint_transition_angle, - const float default_acceptance_radius, const float acceptance_radius_gain, - const float acceptance_radius_max, const float wheel_base, const float max_steer_angle) -{ - // Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment - float acceptance_radius = default_acceptance_radius; - - if (PX4_ISFINITE(_waypoint_transition_angle)) { - const float theta = waypoint_transition_angle / 2.f; - const float min_turning_radius = wheel_base / sinf(max_steer_angle); - const float acceptance_radius_temp = min_turning_radius / tanf(theta); - const float acceptance_radius_temp_scaled = acceptance_radius_gain * - acceptance_radius_temp; // Scale geometric ideal acceptance radius to account for kinematic and dynamic effects - acceptance_radius = math::constrain(acceptance_radius_temp_scaled, default_acceptance_radius, - acceptance_radius_max); - } - - // Publish updated acceptance radius - position_controller_status_s pos_ctrl_status{}; - pos_ctrl_status.acceptance_radius = acceptance_radius; - pos_ctrl_status.timestamp = hrt_absolute_time(); - _position_controller_status_pub.publish(pos_ctrl_status); - return acceptance_radius; -} - -float AckermannPosControl::autoArrivalSpeed(const float cruising_speed, const float miss_speed_min, const float acc_rad, - const int curr_wp_type, const float waypoint_transition_angle, const float max_yaw_rate) -{ - if (!PX4_ISFINITE(waypoint_transition_angle) - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { - return 0.f; // Stop at the waypoint - - } else { - const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); - const float cornering_speed = max_yaw_rate * turning_circle; - return math::constrain(cornering_speed, miss_speed_min, cruising_speed); // Slow down for cornering - } -} - -float AckermannPosControl::autoCruisingSpeed(const float cruising_speed, const float miss_speed_min, - const float distance_to_prev_wp, const float distance_to_curr_wp, const float acc_rad, const float prev_acc_rad, - const float waypoint_transition_angle, const float prev_waypoint_transition_angle, const float max_yaw_rate) -{ - // Catch improper values - if (miss_speed_min < -FLT_EPSILON || miss_speed_min > cruising_speed) { - return cruising_speed; - } - - // Cornering slow down effect - if (distance_to_prev_wp <= prev_acc_rad && prev_acc_rad > FLT_EPSILON && PX4_ISFINITE(prev_waypoint_transition_angle)) { - const float turning_circle = prev_acc_rad * tanf(prev_waypoint_transition_angle / 2.f); - const float cornering_speed = max_yaw_rate * turning_circle; - return math::constrain(cornering_speed, miss_speed_min, cruising_speed); - - } - - if (distance_to_curr_wp <= acc_rad && acc_rad > FLT_EPSILON && PX4_ISFINITE(waypoint_transition_angle)) { - const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); - const float cornering_speed = max_yaw_rate * turning_circle; - return math::constrain(cornering_speed, miss_speed_min, cruising_speed); - - } - - return cruising_speed; // Fallthrough - -} - -void AckermannPosControl::generateVelocitySetpoint() -{ - hrt_abstime timestamp = hrt_absolute_time(); - - if (_rover_position_setpoint_sub.updated()) { - _rover_position_setpoint_sub.copy(&_rover_position_setpoint); - _start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]); - _start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned; - } - - if (_position_controller_status_sub.updated()) { - position_controller_status_s position_controller_status{}; - _position_controller_status_sub.copy(&position_controller_status); - _acceptance_radius = position_controller_status.acceptance_radius; - } - - const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]); - const float distance_to_target = (target_waypoint_ned - _curr_pos_ned).norm(); - - if (distance_to_target > _param_nav_acc_rad.get()) { - - float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : - 0.f; - const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _acceptance_radius : distance_to_target; - float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), - _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); - speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); - - if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { - speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, - fabsf(_rover_position_setpoint.cruising_speed)); - } - - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = timestamp; - - const float yaw_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, - _curr_pos_ned, fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? yaw_setpoint : matrix::wrap_pi( - yaw_setpoint + M_PI_F); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } else { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = timestamp; - rover_velocity_setpoint.speed = 0.f; - rover_velocity_setpoint.bearing = _vehicle_yaw; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - } -} - bool AckermannPosControl::runSanityChecks() { bool ret = true; - if (_param_ro_max_thr_speed.get() < FLT_EPSILON) { - ret = false; - } - - if (_param_ra_wheel_base.get() < FLT_EPSILON) { - ret = false; - } - - if (_param_ra_max_str_ang.get() < FLT_EPSILON) { - ret = false; - } - if (_param_ro_speed_limit.get() < FLT_EPSILON) { ret = false; } - if (_param_ro_yaw_p.get() < FLT_EPSILON) { - ret = false; - } - - _prev_param_check_passed = ret; return ret; } diff --git a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp index fab6c96e30..af2d7581b0 100644 --- a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp +++ b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.hpp @@ -38,26 +38,17 @@ #include // Library includes -#include -#include #include -#include #include -#include #include +#include // uORB includes #include #include #include #include -#include -#include -#include #include -#include -#include -#include #include #include #include @@ -78,19 +69,15 @@ public: ~AckermannPosControl() = default; /** - * @brief Update position control + * @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint. */ void updatePosControl(); /** - * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint. + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. */ - void manualPositionMode(); - - /** - * @brief Generate and publish roverVelocitySetpoint from positionSetpointTriplet. - */ - void autoPositionMode(); + bool runSanityChecks(); protected: /** @@ -104,135 +91,35 @@ private: */ void updateSubscriptions(); - /** - * @brief Generate and publish roverPositionSetpoint from position of trajectorySetpoint. - */ - void generatePositionSetpoint(); - - /** - * @brief Update global/NED waypoint coordinates and acceptance radius. - */ - void updateWaypointsAndAcceptanceRadius(); - - /** - * @brief Publish the acceptance radius for current waypoint based on the angle between a line segment - * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of the vehicle. - * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param default_acceptance_radius Default acceptance radius for waypoints [m]. - * @param acceptance_radius_gain Tuning parameter that scales the geometric optimal acceptance radius for the corner cutting [-]. - * @param acceptance_radius_max Maximum value for the acceptance radius [m]. - * @param wheel_base Rover wheelbase [m]. - * @param max_steer_angle Rover maximum steer angle [rad]. - * @return Updated acceptance radius [m]. - */ - float updateAcceptanceRadius(float waypoint_transition_angle, float default_acceptance_radius, - float acceptance_radius_gain, float acceptance_radius_max, float wheel_base, float max_steer_angle); - - /** - * @brief Calculate the speed at which the rover should arrive at the current waypoint based on the upcoming corner. - * @param cruising_speed Cruising speed [m/s]. - * @param miss_speed_min Minimum speed setpoint [m/s]. - * @param acc_rad Acceptance radius of the current waypoint [m]. - * @param curr_wp_type Type of the current waypoint. - * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] - * @return Speed setpoint [m/s]. - */ - float autoArrivalSpeed(float cruising_speed, float miss_speed_min, float acc_rad, int curr_wp_type, - float waypoint_transition_angle, float max_yaw_rate); - - /** - * @brief Calculate the cruising speed setpoint. During cornering the speed is restricted based on the radius of the corner. - * @param cruising_speed Cruising speed [m/s]. - * @param miss_speed_min Minimum speed setpoint [m/s]. - * @param distance_to_prev_wp Distance to the previous waypoint [m]. - * @param distance_to_curr_wp Distance to the current waypoint [m]. - * @param acc_rad Acceptance radius of the current waypoint [m]. - * @param prev_acc_rad Acceptance radius of the previous waypoint [m]. - * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param prev_waypoint_transition_angle Previous angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] - * @return Speed setpoint [m/s]. - */ - float autoCruisingSpeed(float cruising_speed, float miss_speed_min, float distance_to_prev_wp, - float distance_to_curr_wp, float acc_rad, float prev_acc_rad, float waypoint_transition_angle, - float prev_waypoint_transition_angle, float max_yaw_rate); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); - - /** - * @brief Generate RoverVelocitySetpoint from RoverPositionSetpoint - */ - void generateVelocitySetpoint(); - // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; - uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _rover_position_setpoint_sub{ORB_ID(rover_position_setpoint)}; uORB::Subscription _position_controller_status_sub{ORB_ID(position_controller_status)}; rover_position_setpoint_s _rover_position_setpoint{}; - vehicle_control_mode_s _vehicle_control_mode{}; - offboard_control_mode_s _offboard_control_mode{}; // uORB publications - uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; - uORB::Publication _position_controller_status_pub{ORB_ID(position_controller_status)}; - uORB::Publication _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)}; - uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; + uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; + uORB::Publication _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)}; // Variables Quatf _vehicle_attitude_quaternion{}; Vector2f _curr_pos_ned{}; - Vector2f _pos_ctl_course_direction{}; - Vector2f _pos_ctl_start_position_ned{}; Vector2f _start_ned{}; float _vehicle_yaw{0.f}; float _max_yaw_rate{0.f}; - float _min_speed{0.f}; // Speed at which the maximum yaw rate limit is enforced given the maximum steer angle and wheel base. - int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE}; - bool _course_control{false}; // Indicates if the rover is doing course control in manual position mode. - bool _prev_param_check_passed{true}; - - // Waypoint variables - Vector2f _curr_wp_ned{}; - Vector2f _prev_wp_ned{}; - Vector2f _next_wp_ned{}; - float _acceptance_radius{0.5f}; - float _prev_acceptance_radius{0.5f}; - float _cruising_speed{0.f}; - float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - float _prev_waypoint_transition_angle{0.f}; // Previous Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + float _acceptance_radius{0.f}; // Acceptance radius for the waypoint. // Class Instances MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates DEFINE_PARAMETERS( - (ParamFloat) _param_ro_max_thr_speed, - (ParamFloat) _param_ro_yaw_stick_dz, - (ParamFloat) _param_ro_accel_limit, (ParamFloat) _param_ro_decel_limit, (ParamFloat) _param_ro_jerk_limit, (ParamFloat) _param_ro_speed_limit, - (ParamFloat) _param_ro_speed_th, (ParamFloat) _param_pp_lookahd_gain, (ParamFloat) _param_pp_lookahd_max, (ParamFloat) _param_pp_lookahd_min, - (ParamFloat) _param_ro_yaw_rate_limit, - (ParamFloat) _param_ro_yaw_p, - (ParamFloat) _param_ra_acc_rad_max, - (ParamFloat) _param_ra_acc_rad_gain, - (ParamFloat) _param_ra_max_str_ang, - (ParamFloat) _param_ra_wheel_base, - (ParamFloat) _param_nav_acc_rad - + (ParamFloat) _param_ro_yaw_rate_limit ) }; diff --git a/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp b/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp index f27f6127c2..3c74a3ea48 100644 --- a/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp +++ b/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp @@ -37,8 +37,6 @@ using namespace time_literals; AckermannRateControl::AckermannRateControl(ModuleParams *parent) : ModuleParams(parent) { - _rover_rate_setpoint_pub.advertise(); - _rover_throttle_setpoint_pub.advertise(); _rover_steering_setpoint_pub.advertise(); _rover_rate_status_pub.advertise(); updateParams(); @@ -48,22 +46,80 @@ void AckermannRateControl::updateParams() { ModuleParams::updateParams(); _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; + + // Set up PID controller _pid_yaw_rate.setGains(_param_ro_yaw_rate_p.get(), _param_ro_yaw_rate_i.get(), 0.f); _pid_yaw_rate.setIntegralLimit(1.f); _pid_yaw_rate.setOutputLimit(1.f); - _yaw_rate_setpoint.setSlewRate(_param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F); + + // Set up slew rate + _adjusted_yaw_rate_setpoint.setSlewRate(_param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F); } void AckermannRateControl::updateRateControl() { + updateSubscriptions(); + hrt_abstime timestamp_prev = _timestamp; _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); + if (fabsf(_estimated_speed) > FLT_EPSILON && PX4_ISFINITE(_yaw_rate_setpoint)) { + // Set up feasible yaw rate setpoint + float steering_setpoint{0.f}; + float max_possible_yaw_rate = fabsf(_estimated_speed) * tanf(_param_ra_max_str_ang.get()) / + _param_ra_wheel_base.get(); // Maximum possible yaw rate at current velocity + float yaw_rate_limit = math::min(max_possible_yaw_rate, _max_yaw_rate); + float constrained_yaw_rate = math::constrain(_yaw_rate_setpoint, -yaw_rate_limit, yaw_rate_limit); + + if (_param_ro_yaw_accel_limit.get() > FLT_EPSILON) { // Apply slew rate if configured + if (fabsf(_adjusted_yaw_rate_setpoint.getState() - _vehicle_yaw_rate) > fabsf(constrained_yaw_rate - + _vehicle_yaw_rate)) { + _adjusted_yaw_rate_setpoint.setForcedValue(_vehicle_yaw_rate); + } + + _adjusted_yaw_rate_setpoint.update(constrained_yaw_rate, dt); + + } else { + _adjusted_yaw_rate_setpoint.setForcedValue(constrained_yaw_rate); + } + + // Feed forward + steering_setpoint = atanf(_adjusted_yaw_rate_setpoint.getState() * _param_ra_wheel_base.get() / _estimated_speed); + + // Feedback (Only when driving forwards because backwards driving is NMP and can introduce instability) + if (_estimated_speed > FLT_EPSILON) { + _pid_yaw_rate.setSetpoint(_adjusted_yaw_rate_setpoint.getState()); + steering_setpoint += _pid_yaw_rate.update(_vehicle_yaw_rate, dt); + } + + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = _timestamp; + rover_steering_setpoint.normalized_steering_angle = math::interpolate(steering_setpoint, + -_param_ra_max_str_ang.get(), _param_ra_max_str_ang.get(), -1.f, 1.f); // Normalize steering setpoint + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); + + } else { + _pid_yaw_rate.resetIntegral(); + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = _timestamp; + rover_steering_setpoint.normalized_steering_angle = 0.f; + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); } + + // Publish rate controller status (logging only) + rover_rate_status_s rover_rate_status; + rover_rate_status.timestamp = _timestamp; + rover_rate_status.measured_yaw_rate = _vehicle_yaw_rate; + rover_rate_status.adjusted_yaw_rate_setpoint = _adjusted_yaw_rate_setpoint.getState(); + rover_rate_status.pid_yaw_rate_integral = _pid_yaw_rate.getIntegral(); + _rover_rate_status_pub.publish(rover_rate_status); + +} + +void AckermannRateControl::updateSubscriptions() +{ if (_vehicle_angular_velocity_sub.updated()) { vehicle_angular_velocity_s vehicle_angular_velocity{}; _vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity); @@ -71,107 +127,20 @@ void AckermannRateControl::updateRateControl() vehicle_angular_velocity.xyz[2] : 0.f; } - if (_vehicle_control_mode.flag_control_rates_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { - // Estimate forward speed based on throttle - if (_actuator_motors_sub.updated()) { - actuator_motors_s actuator_motors; - _actuator_motors_sub.copy(&actuator_motors); - _estimated_speed_body_x = math::interpolate(actuator_motors.control[0], -1.f, 1.f, - -_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get()); - _estimated_speed_body_x = fabsf(_estimated_speed_body_x) > _param_ro_speed_th.get() ? _estimated_speed_body_x : 0.f; - } - - if (_vehicle_control_mode.flag_control_manual_enabled) { - generateRateAndThrottleSetpoint(); - } - - generateSteeringSetpoint(); - - } else { // Reset controller and slew rate when rate control is not active - _pid_yaw_rate.resetIntegral(); - _yaw_rate_setpoint.setForcedValue(0.f); + // Estimate forward speed based on throttle + if (_actuator_motors_sub.updated()) { + actuator_motors_s actuator_motors; + _actuator_motors_sub.copy(&actuator_motors); + _estimated_speed = math::interpolate(actuator_motors.control[0], -1.f, 1.f, + -_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get()); + _estimated_speed = fabsf(_estimated_speed) > _param_ro_speed_th.get() ? _estimated_speed : 0.f; } - // Publish rate controller status (logging only) - rover_rate_status_s rover_rate_status; - rover_rate_status.timestamp = _timestamp; - rover_rate_status.measured_yaw_rate = _vehicle_yaw_rate; - rover_rate_status.adjusted_yaw_rate_setpoint = _yaw_rate_setpoint.getState(); - rover_rate_status.pid_yaw_rate_integral = _pid_yaw_rate.getIntegral(); - _rover_rate_status_pub.publish(rover_rate_status); - -} - -void AckermannRateControl::generateRateAndThrottleSetpoint() -{ - const bool acro_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled - && !_vehicle_control_mode.flag_control_position_enabled && !_vehicle_control_mode.flag_control_attitude_enabled; - - if (acro_mode_enabled && _manual_control_setpoint_sub.updated()) { // Acro Mode - manual_control_setpoint_s manual_control_setpoint{}; - - if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - rover_rate_setpoint_s rover_rate_setpoint{}; - rover_rate_setpoint.timestamp = _timestamp; - rover_rate_setpoint.yaw_rate_setpoint = matrix::sign(_estimated_speed_body_x) * math::interpolate - (manual_control_setpoint.roll, -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); - _rover_rate_setpoint_pub.publish(rover_rate_setpoint); - } - - } -} - -void AckermannRateControl::generateSteeringSetpoint() -{ if (_rover_rate_setpoint_sub.updated()) { - _rover_rate_setpoint_sub.copy(&_rover_rate_setpoint); - + rover_rate_setpoint_s rover_rate_setpoint{}; + _rover_rate_setpoint_sub.copy(&rover_rate_setpoint); + _yaw_rate_setpoint = rover_rate_setpoint.yaw_rate_setpoint; } - - float steering_setpoint{0.f}; - - if (fabsf(_estimated_speed_body_x) > FLT_EPSILON) { - // Set up feasible yaw rate setpoint - float max_possible_yaw_rate = fabsf(_estimated_speed_body_x) * tanf(_param_ra_max_str_ang.get()) / - _param_ra_wheel_base.get(); // Maximum possible yaw rate at current velocity - float yaw_rate_limit = math::min(max_possible_yaw_rate, _max_yaw_rate); - float constrained_yaw_rate = math::constrain(_rover_rate_setpoint.yaw_rate_setpoint, -yaw_rate_limit, yaw_rate_limit); - - if (_param_ro_yaw_accel_limit.get() > FLT_EPSILON) { // Apply slew rate if configured - if (fabsf(_yaw_rate_setpoint.getState() - _vehicle_yaw_rate) > fabsf(constrained_yaw_rate - - _vehicle_yaw_rate)) { - _yaw_rate_setpoint.setForcedValue(_vehicle_yaw_rate); - } - - _yaw_rate_setpoint.update(constrained_yaw_rate, _dt); - - } else { - _yaw_rate_setpoint.setForcedValue(constrained_yaw_rate); - } - - // Feed forward - steering_setpoint = atanf(_yaw_rate_setpoint.getState() * _param_ra_wheel_base.get() / _estimated_speed_body_x); - - // Feedback (Only when driving forwards because backwards driving is NMP and can introduce instability) - if (_estimated_speed_body_x > FLT_EPSILON) { - _pid_yaw_rate.setSetpoint(_yaw_rate_setpoint.getState()); - steering_setpoint += _pid_yaw_rate.update(_vehicle_yaw_rate, _dt); - } - - } else { - _pid_yaw_rate.resetIntegral(); - } - - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = _timestamp; - rover_steering_setpoint.normalized_steering_angle = math::interpolate(steering_setpoint, - -_param_ra_max_str_ang.get(), _param_ra_max_str_ang.get(), -1.f, 1.f); // Normalize steering setpoint - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); } bool AckermannRateControl::runSanityChecks() @@ -180,44 +149,31 @@ bool AckermannRateControl::runSanityChecks() if (_param_ro_max_thr_speed.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("ackermann_rate_control_conf_invalid_max_thr_speed"), events::Log::Error, - "Invalid configuration of necessary parameter RO_MAX_THR_SPEED", _param_ro_max_thr_speed.get()); - } + events::send(events::ID("ackermann_rate_control_conf_invalid_max_thr_speed"), events::Log::Error, + "Invalid configuration of necessary parameter RO_MAX_THR_SPEED", _param_ro_max_thr_speed.get()); } if (_param_ra_wheel_base.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("ackermann_rate_control_conf_invalid_wheel_base"), events::Log::Error, - "Invalid configuration of necessary parameter RA_WHEEL_BASE", _param_ra_wheel_base.get()); - } + events::send(events::ID("ackermann_rate_control_conf_invalid_wheel_base"), events::Log::Error, + "Invalid configuration of necessary parameter RA_WHEEL_BASE", _param_ra_wheel_base.get()); } if (_param_ra_max_str_ang.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("ackermann_rate_control_conf_invalid_max_str_ang"), events::Log::Error, - "Invalid configuration of necessary parameter RA_MAX_STR_ANG", _param_ra_max_str_ang.get()); - } + events::send(events::ID("ackermann_rate_control_conf_invalid_max_str_ang"), events::Log::Error, + "Invalid configuration of necessary parameter RA_MAX_STR_ANG", _param_ra_max_str_ang.get()); } if (_param_ro_yaw_rate_limit.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("ackermann_rate_control_conf_invalid_yaw_rate_lim"), events::Log::Error, - "Invalid configuration of necessary parameter RO_YAW_RATE_LIM", _param_ro_yaw_rate_limit.get()); - } + events::send(events::ID("ackermann_rate_control_conf_invalid_yaw_rate_lim"), events::Log::Error, + "Invalid configuration of necessary parameter RO_YAW_RATE_LIM", _param_ro_yaw_rate_limit.get()); } - _prev_param_check_passed = ret; return ret; } diff --git a/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.hpp b/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.hpp index 8f0891cb48..d5014a4306 100644 --- a/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.hpp +++ b/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.hpp @@ -47,9 +47,6 @@ #include #include #include -#include -#include -#include #include #include #include @@ -69,10 +66,21 @@ public: ~AckermannRateControl() = default; /** - * @brief Update rate controller. + * @brief Generate and publish roverSteeringSetpoint from roverRateSetpoint. */ void updateRateControl(); + /** + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. + */ + bool runSanityChecks(); + + /** + * @brief Reset rate controller. + */ + void reset() {_pid_yaw_rate.resetIntegral(); _yaw_rate_setpoint = NAN;}; + protected: /** * @brief Update the parameters of the module. @@ -80,50 +88,31 @@ protected: void updateParams() override; private: - /** - * @brief Generate and publish roverRateSetpoint and roverThrottleSetpoint from manualControlSetpoint (Acro Mode). + * @brief Update uORB subscriptions used in rate controller. */ - void generateRateAndThrottleSetpoint(); - - /** - * @brief Generate and publish roverSteeringSetpoint from RoverRateSetpoint. - */ - void generateSteeringSetpoint(); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); + void updateSubscriptions(); // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _rover_rate_setpoint_sub{ORB_ID(rover_rate_setpoint)}; uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; - vehicle_control_mode_s _vehicle_control_mode{}; - rover_rate_setpoint_s _rover_rate_setpoint{}; // uORB publications - uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; - uORB::Publication _rover_rate_status_pub{ORB_ID(rover_rate_status)}; + uORB::Publication _rover_rate_status_pub{ORB_ID(rover_rate_status)}; // Variables - float _estimated_speed_body_x{0.f}; /*Vehicle speed estimated by interpolating [actuatorMotorSetpoint, _estimated_speed_body_x] + float _estimated_speed{0.f}; /*Vehicle speed estimated by interpolating [actuatorMotorSetpoint, _estimated_speed] between [0, 0] and [1, _param_ro_max_thr_speed].*/ float _max_yaw_rate{0.f}; float _vehicle_yaw_rate{0.f}; + float _yaw_rate_setpoint{NAN}; hrt_abstime _timestamp{0}; - float _dt{0.f}; // Time since last update [s]. - bool _prev_param_check_passed{true}; // Controllers PID _pid_yaw_rate; - SlewRate _yaw_rate_setpoint{0.f}; + SlewRate _adjusted_yaw_rate_setpoint{0.f}; DEFINE_PARAMETERS( (ParamFloat) _param_ro_max_thr_speed, diff --git a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp index 8d9bf88e8b..2804d0b8a6 100644 --- a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp +++ b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp @@ -38,50 +38,68 @@ using namespace time_literals; AckermannVelControl::AckermannVelControl(ModuleParams *parent) : ModuleParams(parent) { _rover_throttle_setpoint_pub.advertise(); - _rover_velocity_status_pub.advertise(); - _rover_velocity_setpoint_pub.advertise(); _rover_attitude_setpoint_pub.advertise(); + _rover_velocity_status_pub.advertise(); updateParams(); } void AckermannVelControl::updateParams() { ModuleParams::updateParams(); + + // Set up PID controller _pid_speed.setGains(_param_ro_speed_p.get(), _param_ro_speed_i.get(), 0.f); _pid_speed.setIntegralLimit(1.f); _pid_speed.setOutputLimit(1.f); + // Set up slew rate if (_param_ro_accel_limit.get() > FLT_EPSILON) { - _speed_setpoint.setSlewRate(_param_ro_accel_limit.get()); + _adjusted_speed_setpoint.setSlewRate(_param_ro_accel_limit.get()); } } void AckermannVelControl::updateVelControl() { - const hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - updateSubscriptions(); - if ((_vehicle_control_mode.flag_control_velocity_enabled) && _vehicle_control_mode.flag_armed && runSanityChecks()) { - if (_vehicle_control_mode.flag_control_offboard_enabled) { // Offboard Velocity Control - generateVelocitySetpoint(); - } + const hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - generateAttitudeAndThrottleSetpoint(); + // Attitude Setpoint + if (PX4_ISFINITE(_bearing_setpoint)) { + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = _timestamp; + rover_attitude_setpoint.yaw_setpoint = _bearing_setpoint; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + } - } else { // Reset controller and slew rate when position control is not active - _pid_speed.resetIntegral(); - _speed_setpoint.setForcedValue(0.f); + // Throttle Setpoint + if (PX4_ISFINITE(_speed_setpoint)) { + const float speed_setpoint = math::constrain(_speed_setpoint, -_param_ro_speed_limit.get(), + _param_ro_speed_limit.get()); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = _timestamp; + rover_throttle_setpoint.throttle_body_x = RoverControl::speedControl(_adjusted_speed_setpoint, _pid_speed, + speed_setpoint, _vehicle_speed, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(), + _param_ro_max_thr_speed.get(), dt); + rover_throttle_setpoint.throttle_body_y = NAN; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); + + } else { + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = _timestamp; + rover_throttle_setpoint.throttle_body_x = 0.f; + rover_throttle_setpoint.throttle_body_y = NAN; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); } // Publish position controller status (logging only) rover_velocity_status_s rover_velocity_status; rover_velocity_status.timestamp = _timestamp; rover_velocity_status.measured_speed_body_x = _vehicle_speed; - rover_velocity_status.adjusted_speed_body_x_setpoint = _speed_setpoint.getState(); + rover_velocity_status.adjusted_speed_body_x_setpoint = _adjusted_speed_setpoint.getState(); rover_velocity_status.pid_throttle_body_x_integral = _pid_speed.getIntegral(); rover_velocity_status.measured_speed_body_y = NAN; rover_velocity_status.adjusted_speed_body_y_setpoint = NAN; @@ -91,10 +109,6 @@ void AckermannVelControl::updateVelControl() void AckermannVelControl::updateSubscriptions() { - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); - } - if (_vehicle_attitude_sub.updated()) { vehicle_attitude_s vehicle_attitude{}; _vehicle_attitude_sub.copy(&vehicle_attitude); @@ -105,68 +119,18 @@ void AckermannVelControl::updateSubscriptions() if (_vehicle_local_position_sub.updated()) { vehicle_local_position_s vehicle_local_position{}; _vehicle_local_position_sub.copy(&vehicle_local_position); - Vector3f velocity_ned(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz); Vector3f velocity_xyz = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_ned); Vector2f velocity_2d = Vector2f(velocity_xyz(0), velocity_xyz(1)); _vehicle_speed = velocity_2d.norm() > _param_ro_speed_th.get() ? sign(velocity_2d(0)) * velocity_2d.norm() : 0.f; } -} - -void AckermannVelControl::generateVelocitySetpoint() -{ - trajectory_setpoint_s trajectory_setpoint{}; - _trajectory_setpoint_sub.copy(&trajectory_setpoint); - - if (_offboard_control_mode_sub.updated()) { - _offboard_control_mode_sub.copy(&_offboard_control_mode); - } - - const bool offboard_vel_control = _offboard_control_mode.velocity && !_offboard_control_mode.position; - - const Vector2f velocity_in_local_frame(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]); - - if (offboard_vel_control && velocity_in_local_frame.isAllFinite()) { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = velocity_in_local_frame.norm(); - rover_velocity_setpoint.bearing = atan2f(velocity_in_local_frame(1), velocity_in_local_frame(0)); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - } -} - -void AckermannVelControl::generateAttitudeAndThrottleSetpoint() -{ if (_rover_velocity_setpoint_sub.updated()) { - _rover_velocity_setpoint_sub.copy(&_rover_velocity_setpoint); + rover_velocity_setpoint_s rover_velocity_setpoint; + _rover_velocity_setpoint_sub.copy(&rover_velocity_setpoint); + _speed_setpoint = rover_velocity_setpoint.speed; + _bearing_setpoint = rover_velocity_setpoint.bearing; } - - // Attitude Setpoint - if (fabsf(_rover_velocity_setpoint.speed) < FLT_EPSILON) { - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = _vehicle_yaw; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - - } else if (PX4_ISFINITE(_rover_velocity_setpoint.bearing)) { - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = _rover_velocity_setpoint.bearing; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } - - // Throttle Setpoint - const float speed_setpoint = math::constrain(_rover_velocity_setpoint.speed, -_param_ro_speed_limit.get(), - _param_ro_speed_limit.get()); - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = RoverControl::speedControl(_speed_setpoint, _pid_speed, - speed_setpoint, _vehicle_speed, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(), - _param_ro_max_thr_speed.get(), _dt); - rover_throttle_setpoint.throttle_body_y = NAN; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - } bool AckermannVelControl::runSanityChecks() @@ -179,14 +143,10 @@ bool AckermannVelControl::runSanityChecks() if (_param_ro_speed_limit.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("ackermann_vel_control_conf_invalid_speed_lim"), events::Log::Error, - "Invalid configuration of necessary parameter RO_SPEED_LIM", _param_ro_speed_limit.get()); - } + events::send(events::ID("ackermann_vel_control_conf_invalid_speed_lim"), events::Log::Error, + "Invalid configuration of necessary parameter RO_SPEED_LIM", _param_ro_speed_limit.get()); } - _prev_param_check_passed = ret; return ret; } diff --git a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.hpp b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.hpp index 74dea1693c..42f437293c 100644 --- a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.hpp +++ b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.hpp @@ -51,10 +51,7 @@ #include #include #include -#include -#include #include -#include #include using namespace matrix; @@ -73,10 +70,21 @@ public: ~AckermannVelControl() = default; /** - * @brief Update velocity controller. + * @brief Generate and publish roverAttitudeSetpoint and RoverThrottleSetpoint from roverVelocitySetpoint. */ void updateVelControl(); + /** + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. + */ + bool runSanityChecks(); + + /** + * @brief Reset velocity controller. + */ + void reset() {_pid_speed.resetIntegral(); _speed_setpoint = NAN; _bearing_setpoint = NAN; _adjusted_speed_setpoint.setForcedValue(0.f);}; + protected: /** * @brief Update the parameters of the module. @@ -85,55 +93,32 @@ protected: private: /** - * @brief Update uORB subscriptions used in velocity controller. + * @brief Update uORB subscriptions used in position controller. */ void updateSubscriptions(); - /** - * @brief Generate and publish roverVelocitySetpoint from velocity of trajectorySetpoint. - */ - void generateVelocitySetpoint(); - - /** - * @brief Generate and publish roverAttitudeSetpoint and roverThrottleSetpoint - * from roverVelocitySetpoint. - */ - void generateAttitudeAndThrottleSetpoint(); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); - // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _rover_velocity_setpoint_sub{ORB_ID(rover_velocity_setpoint)}; - vehicle_control_mode_s _vehicle_control_mode{}; - offboard_control_mode_s _offboard_control_mode{}; // uORB publications uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; uORB::Publication _rover_velocity_status_pub{ORB_ID(rover_velocity_status)}; uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; - rover_velocity_setpoint_s _rover_velocity_setpoint{}; // Variables hrt_abstime _timestamp{0}; Quatf _vehicle_attitude_quaternion{}; float _vehicle_speed{0.f}; // [m/s] Positiv: Forwards, Negativ: Backwards float _vehicle_yaw{0.f}; - float _dt{0.f}; - bool _prev_param_check_passed{true}; + float _speed_setpoint{NAN}; + float _bearing_setpoint{NAN}; // Controllers PID _pid_speed; - SlewRate _speed_setpoint; + SlewRate _adjusted_speed_setpoint; DEFINE_PARAMETERS( (ParamFloat) _param_ro_max_thr_speed, diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index d57d6a0d8c..fcc0f059c6 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -39,8 +39,6 @@ RoverAckermann::RoverAckermann() : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) { - _rover_throttle_setpoint_pub.advertise(); - _rover_steering_setpoint_pub.advertise(); updateParams(); } @@ -53,49 +51,472 @@ bool RoverAckermann::init() void RoverAckermann::updateParams() { ModuleParams::updateParams(); + _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; + + if (_param_ra_wheel_base.get() > FLT_EPSILON && _max_yaw_rate > FLT_EPSILON + && _param_ra_max_str_ang.get() > FLT_EPSILON) { + _min_speed = _param_ra_wheel_base.get() * _max_yaw_rate / tanf(_param_ra_max_str_ang.get()); + } } void RoverAckermann::Run() { if (_parameter_update_sub.updated()) { + parameter_update_s param_update{}; + _parameter_update_sub.copy(¶m_update); updateParams(); + runSanityChecks(); } if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); + vehicle_control_mode_s vehicle_control_mode{}; + _vehicle_control_mode_sub.copy(&vehicle_control_mode); + + // Run sanity checks if the control mode changes (Note: This has to be done this way, because the topic is periodically updated and not on changes) + if (vehicle_control_mode.flag_control_position_enabled != _vehicle_control_mode.flag_control_position_enabled || + vehicle_control_mode.flag_control_velocity_enabled != _vehicle_control_mode.flag_control_velocity_enabled || + vehicle_control_mode.flag_control_attitude_enabled != _vehicle_control_mode.flag_control_attitude_enabled || + vehicle_control_mode.flag_control_rates_enabled != _vehicle_control_mode.flag_control_rates_enabled) { + _vehicle_control_mode = vehicle_control_mode; + runSanityChecks(); + + } else { + _vehicle_control_mode = vehicle_control_mode; + } + } - const bool full_manual_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled - && !_vehicle_control_mode.flag_control_position_enabled && !_vehicle_control_mode.flag_control_attitude_enabled - && !_vehicle_control_mode.flag_control_rates_enabled; + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status{}; + _vehicle_status_sub.copy(&vehicle_status); - if (full_manual_mode_enabled) { // Manual mode - generateSteeringAndThrottleSetpoint(); + // Reset all controllers if the navigation state changes + if (vehicle_status.nav_state != _nav_state) { reset();} + + _nav_state = vehicle_status.nav_state; } + if (_vehicle_control_mode.flag_armed && _sanity_checks_passed) { + // Generate setpoints + if (_vehicle_control_mode.flag_control_manual_enabled) { + manualControl(); + + } else if (_vehicle_control_mode.flag_control_auto_enabled) { + autoPositionMode(); + + } else if (_vehicle_control_mode.flag_control_offboard_enabled) { + offboardControl(); + } + + updateControllers(); + + } else if (_was_armed) { // Reset all controllers and stop the vehicle + reset(); + _ackermann_act_control.stopVehicle(); + _was_armed = false; + } - _ackermann_pos_control.updatePosControl(); - _ackermann_vel_control.updateVelControl(); - _ackermann_att_control.updateAttControl(); - _ackermann_rate_control.updateRateControl(); - _ackermann_act_control.updateActControl(); } -void RoverAckermann::generateSteeringAndThrottleSetpoint() +void RoverAckermann::manualControl() +{ + switch (_nav_state) { + case vehicle_status_s::NAVIGATION_STATE_MANUAL: + manualManualMode(); + break; + + case vehicle_status_s::NAVIGATION_STATE_ACRO: + manualAcroMode(); + break; + + case vehicle_status_s::NAVIGATION_STATE_STAB: + manualStabMode(); + break; + + case vehicle_status_s::NAVIGATION_STATE_POSCTL: + manualPositionMode(); + break; + } +} + +void RoverAckermann::manualManualMode() { manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = hrt_absolute_time(); + rover_steering_setpoint.normalized_steering_angle = manual_control_setpoint.roll; + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); +} - if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = hrt_absolute_time(); - rover_steering_setpoint.normalized_steering_angle = manual_control_setpoint.roll; - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = hrt_absolute_time(); - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); +void RoverAckermann::manualAcroMode() +{ + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * math::interpolate + (manual_control_setpoint.roll, -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); +} + +void RoverAckermann::manualStabMode() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); } + + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); + + const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), + _max_yaw_rate / _param_ro_yaw_p.get()); + + if (fabsf(yaw_delta) > FLT_EPSILON + || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { // Closed loop yaw rate control + _stab_yaw_setpoint = NAN; + const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + matrix::sign(manual_control_setpoint.throttle) * yaw_delta); + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = yaw_setpoint; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + + } else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw) + if (!PX4_ISFINITE(_stab_yaw_setpoint)) { + _stab_yaw_setpoint = _vehicle_yaw; + } + + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + } +} + +void RoverAckermann::manualPositionMode() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); + } + + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + + if (!_global_ned_proj_ref.isInitialized() + || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { + _global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, + vehicle_local_position.ref_timestamp); + } + + _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); + } + + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + + const float speed_setpoint = math::interpolate(manual_control_setpoint.throttle, + -1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); + const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), + _max_yaw_rate / _param_ro_yaw_p.get()); + + if (fabsf(yaw_delta) > FLT_EPSILON + || fabsf(speed_setpoint) < FLT_EPSILON) { // Closed loop yaw rate control + _pos_ctl_course_direction = Vector2f(NAN, NAN); + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover + const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + sign(speed_setpoint) * yaw_delta); + const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); + const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * + pos_ctl_course_direction; + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + + } else { // Course control if the steering input is zero (keep driving on a straight line) + if (!_pos_ctl_course_direction.isAllFinite()) { + _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); + _pos_ctl_start_position_ned = _curr_pos_ned; + } + + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover + const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned; + const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); + const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * + vector_scaling * _pos_ctl_course_direction; + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); + rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + } +} + +void RoverAckermann::autoPositionMode() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); + } + + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + + if (!_global_ned_proj_ref.isInitialized() + || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { + _global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, + vehicle_local_position.ref_timestamp); + } + + _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); + } + + if (_position_setpoint_triplet_sub.updated()) { + autoUpdateWaypointsAndAcceptanceRadius(); + } + + // Distances to waypoints + const float distance_to_prev_wp = sqrt(powf(_curr_pos_ned(0) - _prev_wp_ned(0), + 2) + powf(_curr_pos_ned(1) - _prev_wp_ned(1), 2)); + const float distance_to_curr_wp = sqrt(powf(_curr_pos_ned(0) - _curr_wp_ned(0), + 2) + powf(_curr_pos_ned(1) - _curr_wp_ned(1), 2)); + + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = _curr_wp_ned(0); + rover_position_setpoint.position_ned[1] = _curr_wp_ned(1); + rover_position_setpoint.start_ned[0] = _prev_wp_ned(0); + rover_position_setpoint.start_ned[1] = _prev_wp_ned(1); + rover_position_setpoint.arrival_speed = autoArrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius, _curr_wp_type, + _waypoint_transition_angle, _max_yaw_rate); + rover_position_setpoint.cruising_speed = autoCruisingSpeed(_cruising_speed, _min_speed, distance_to_prev_wp, + distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _waypoint_transition_angle, + _prev_waypoint_transition_angle, _max_yaw_rate); + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); +} + +void RoverAckermann::autoUpdateWaypointsAndAcceptanceRadius() +{ + position_setpoint_triplet_s position_setpoint_triplet{}; + _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); + _curr_wp_type = position_setpoint_triplet.current.type; + + RoverControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet, + _curr_pos_ned, _global_ned_proj_ref); + + _prev_waypoint_transition_angle = _waypoint_transition_angle; + _waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned, _next_wp_ned); + + // Update acceptance radius + _prev_acceptance_radius = _acceptance_radius; + + if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) { + _acceptance_radius = autoUpdateAcceptanceRadius(_waypoint_transition_angle, _param_nav_acc_rad.get(), + _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_str_ang.get()); + + } else { + _acceptance_radius = _param_nav_acc_rad.get(); + } + + // Waypoint cruising speed + _cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain( + position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get(); +} + +float RoverAckermann::autoUpdateAcceptanceRadius(const float waypoint_transition_angle, + const float default_acceptance_radius, const float acceptance_radius_gain, + const float acceptance_radius_max, const float wheel_base, const float max_steer_angle) +{ + // Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment + float acceptance_radius = default_acceptance_radius; + + if (PX4_ISFINITE(_waypoint_transition_angle)) { + const float theta = waypoint_transition_angle / 2.f; + const float min_turning_radius = wheel_base / sinf(max_steer_angle); + const float acceptance_radius_temp = min_turning_radius / tanf(theta); + const float acceptance_radius_temp_scaled = acceptance_radius_gain * + acceptance_radius_temp; // Scale geometric ideal acceptance radius to account for kinematic and dynamic effects + acceptance_radius = math::constrain(acceptance_radius_temp_scaled, default_acceptance_radius, + acceptance_radius_max); + } + + // Publish updated acceptance radius + position_controller_status_s pos_ctrl_status{}; + pos_ctrl_status.acceptance_radius = acceptance_radius; + pos_ctrl_status.timestamp = hrt_absolute_time(); + _position_controller_status_pub.publish(pos_ctrl_status); + return acceptance_radius; +} + +float RoverAckermann::autoArrivalSpeed(const float cruising_speed, const float miss_speed_min, const float acc_rad, + const int curr_wp_type, const float waypoint_transition_angle, const float max_yaw_rate) +{ + if (!PX4_ISFINITE(waypoint_transition_angle) + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { + return 0.f; // Stop at the waypoint + + } else { + const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); + const float cornering_speed = max_yaw_rate * turning_circle; + return math::constrain(cornering_speed, miss_speed_min, cruising_speed); // Slow down for cornering + } +} + +float RoverAckermann::autoCruisingSpeed(const float cruising_speed, const float miss_speed_min, + const float distance_to_prev_wp, const float distance_to_curr_wp, const float acc_rad, const float prev_acc_rad, + const float waypoint_transition_angle, const float prev_waypoint_transition_angle, const float max_yaw_rate) +{ + // Catch improper values + if (miss_speed_min < -FLT_EPSILON || miss_speed_min > cruising_speed) { + return cruising_speed; + } + + // Cornering slow down effect + if (distance_to_prev_wp <= prev_acc_rad && prev_acc_rad > FLT_EPSILON && PX4_ISFINITE(prev_waypoint_transition_angle)) { + const float turning_circle = prev_acc_rad * tanf(prev_waypoint_transition_angle / 2.f); + const float cornering_speed = max_yaw_rate * turning_circle; + return math::constrain(cornering_speed, miss_speed_min, cruising_speed); + + } + + if (distance_to_curr_wp <= acc_rad && acc_rad > FLT_EPSILON && PX4_ISFINITE(waypoint_transition_angle)) { + const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); + const float cornering_speed = max_yaw_rate * turning_circle; + return math::constrain(cornering_speed, miss_speed_min, cruising_speed); + + } + + return cruising_speed; // Fallthrough + +} + +void RoverAckermann::offboardControl() +{ + offboard_control_mode_s offboard_control_mode{}; + _offboard_control_mode_sub.copy(&offboard_control_mode); + + trajectory_setpoint_s trajectory_setpoint{}; + _trajectory_setpoint_sub.copy(&trajectory_setpoint); + + if (offboard_control_mode.position) { + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; + rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.cruising_speed = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + + } else if (offboard_control_mode.velocity) { + const Vector2f velocity_ned(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]); + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = hrt_absolute_time(); + rover_velocity_setpoint.speed = velocity_ned.norm(); + rover_velocity_setpoint.bearing = atan2f(velocity_ned(1), velocity_ned(0)); + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + } +} + +void RoverAckermann::updateControllers() +{ + if (_vehicle_control_mode.flag_control_position_enabled) { + _ackermann_pos_control.updatePosControl(); + } + + if (_vehicle_control_mode.flag_control_velocity_enabled) { + _ackermann_vel_control.updateVelControl(); + } + + if (_vehicle_control_mode.flag_control_attitude_enabled) { + _ackermann_att_control.updateAttControl(); + } + + if (_vehicle_control_mode.flag_control_rates_enabled) { + _ackermann_rate_control.updateRateControl(); + } + + if (_vehicle_control_mode.flag_control_allocation_enabled) { + _ackermann_act_control.updateActControl(); + } +} + +void RoverAckermann::runSanityChecks() +{ + if (_vehicle_control_mode.flag_control_rates_enabled && !_ackermann_rate_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + if (_vehicle_control_mode.flag_control_attitude_enabled && !_ackermann_att_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + if (_vehicle_control_mode.flag_control_velocity_enabled && !_ackermann_vel_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + if (_vehicle_control_mode.flag_control_position_enabled && !_ackermann_pos_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + _sanity_checks_passed = true; +} + +void RoverAckermann::reset() +{ + _ackermann_vel_control.reset(); + _ackermann_att_control.reset(); + _ackermann_rate_control.reset(); + _stab_yaw_setpoint = NAN; + _pos_ctl_course_direction = Vector2f(NAN, NAN); + _pos_ctl_start_position_ned = Vector2f(NAN, NAN); + _curr_pos_ned = Vector2f(NAN, NAN); } int RoverAckermann::task_spawn(int argc, char *argv[]) diff --git a/src/modules/rover_ackermann/RoverAckermann.hpp b/src/modules/rover_ackermann/RoverAckermann.hpp index 0655ba9dda..968f99ed4f 100644 --- a/src/modules/rover_ackermann/RoverAckermann.hpp +++ b/src/modules/rover_ackermann/RoverAckermann.hpp @@ -40,14 +40,30 @@ #include #include +// Library includes +#include +#include + // uORB includes #include #include +#include #include +#include +#include +#include +#include +#include +#include +#include #include #include -#include -#include +#include +#include +#include +#include +#include +#include // Local includes #include "AckermannActControl/AckermannActControl.hpp" @@ -87,19 +103,128 @@ private: void Run() override; /** - * @brief Generate and publish roverSteeringSetpoint and roverThrottleSetpoint from manualControlSetpoint (Manual Mode). + * @brief Handle manual control */ - void generateSteeringAndThrottleSetpoint(); + void manualControl(); + + /** + * @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint. + */ + void manualManualMode(); + + /** + * @brief Generate and publish roverThrottleSetpoint and RoverRateSetpoint from manualControlSetpoint. + */ + void manualAcroMode(); + + /** + * @brief Generate and publish roverThrottleSetpoint and RoverAttitudeSetpoint from manualControlSetpoint. + */ + void manualStabMode(); + + /** + * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint. + */ + void manualPositionMode(); + + /** + * @brief Generate and publish roverVelocitySetpoint from positionSetpointTriplet. + */ + void autoPositionMode(); + + /** + * @brief Update global/NED waypoint coordinates and acceptance radius. + */ + void autoUpdateWaypointsAndAcceptanceRadius(); + + /** + * @brief Publish the acceptance radius for current waypoint based on the angle between a line segment + * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of the vehicle. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param default_acceptance_radius Default acceptance radius for waypoints [m]. + * @param acceptance_radius_gain Tuning parameter that scales the geometric optimal acceptance radius for the corner cutting [-]. + * @param acceptance_radius_max Maximum value for the acceptance radius [m]. + * @param wheel_base Rover wheelbase [m]. + * @param max_steer_angle Rover maximum steer angle [rad]. + * @return Updated acceptance radius [m]. + */ + float autoUpdateAcceptanceRadius(float waypoint_transition_angle, float default_acceptance_radius, + float acceptance_radius_gain, float acceptance_radius_max, float wheel_base, float max_steer_angle); + + /** + * @brief Calculate the speed at which the rover should arrive at the current waypoint based on the upcoming corner. + * @param cruising_speed Cruising speed [m/s]. + * @param miss_speed_min Minimum speed setpoint [m/s]. + * @param acc_rad Acceptance radius of the current waypoint [m]. + * @param curr_wp_type Type of the current waypoint. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] + * @return Speed setpoint [m/s]. + */ + float autoArrivalSpeed(float cruising_speed, float miss_speed_min, float acc_rad, int curr_wp_type, + float waypoint_transition_angle, float max_yaw_rate); + + /** + * @brief Calculate the cruising speed setpoint. During cornering the speed is restricted based on the radius of the corner. + * @param cruising_speed Cruising speed [m/s]. + * @param miss_speed_min Minimum speed setpoint [m/s]. + * @param distance_to_prev_wp Distance to the previous waypoint [m]. + * @param distance_to_curr_wp Distance to the current waypoint [m]. + * @param acc_rad Acceptance radius of the current waypoint [m]. + * @param prev_acc_rad Acceptance radius of the previous waypoint [m]. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param prev_waypoint_transition_angle Previous angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] + * @return Speed setpoint [m/s]. + */ + float autoCruisingSpeed(float cruising_speed, float miss_speed_min, float distance_to_prev_wp, + float distance_to_curr_wp, float acc_rad, float prev_acc_rad, float waypoint_transition_angle, + float prev_waypoint_transition_angle, float max_yaw_rate); + + /** + * @brief Translate trajectorySetpoint to roverSetpoints and publish them + */ + void offboardControl(); + + /** + * @brief Update the controllers + */ + void updateControllers(); + + /** + * @brief Check proper parameter setup for the controllers + * + * Modifies: + * + * - _sanity_checks_passed: true if checks for all active controllers pass + */ + void runSanityChecks(); + + /** + * @brief Reset controllers and manual mode variables. + */ + void reset(); // uORB subscriptions + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; + uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; + uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; vehicle_control_mode_s _vehicle_control_mode{}; // uORB publications - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; - uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; + uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; + uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; + uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; + uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; + uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; + uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; + uORB::Publication _position_controller_status_pub{ORB_ID(position_controller_status)}; // Class instances AckermannActControl _ackermann_act_control{this}; @@ -108,4 +233,43 @@ private: AckermannVelControl _ackermann_vel_control{this}; AckermannPosControl _ackermann_pos_control{this}; + // Variables + MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates + Quatf _vehicle_attitude_quaternion{}; + float _max_yaw_rate{NAN}; + float _vehicle_yaw{NAN}; + float _min_speed{0.f}; // Speed at which the maximum yaw rate limit is enforced given the maximum steer angle and wheel base. + int _nav_state{0}; // Navigation state of the vehicle + bool _sanity_checks_passed{true}; // True if checks for all active controllers pass + bool _was_armed{false}; // True if the vehicle was armed before the last reset + + // Auto Mode Variables + Vector2f _curr_wp_ned{}; + Vector2f _prev_wp_ned{}; + Vector2f _next_wp_ned{}; + float _acceptance_radius{0.5f}; + float _prev_acceptance_radius{0.5f}; + float _cruising_speed{0.f}; + float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + float _prev_waypoint_transition_angle{0.f}; // Previous Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE}; + + // Manual Mode Variables + Vector2f _pos_ctl_course_direction{NAN, NAN}; + Vector2f _pos_ctl_start_position_ned{NAN, NAN}; + Vector2f _curr_pos_ned{NAN, NAN}; + float _stab_yaw_setpoint{NAN}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_ro_yaw_rate_limit, + (ParamFloat) _param_ro_yaw_p, + (ParamFloat) _param_ro_yaw_stick_dz, + (ParamFloat) _param_pp_lookahd_max, + (ParamFloat) _param_ro_speed_limit, + (ParamFloat) _param_ra_wheel_base, + (ParamFloat) _param_ra_max_str_ang, + (ParamFloat) _param_nav_acc_rad, + (ParamFloat) _param_ra_acc_rad_max, + (ParamFloat) _param_ra_acc_rad_gain + ) }; From a129a29793f85648176795ed46a804ef423406b2 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 13 May 2025 10:22:07 +0200 Subject: [PATCH 047/130] ackermann: split modes into seperate folder --- src/modules/rover_ackermann/CMakeLists.txt | 4 + .../DriveModes/AutoMode/AutoMode.cpp | 196 ++++++++++ .../DriveModes/AutoMode/AutoMode.hpp | 161 ++++++++ .../DriveModes/AutoMode/CMakeLists.txt | 38 ++ .../rover_ackermann/DriveModes/CMakeLists.txt | 36 ++ .../DriveModes/ManualMode/CMakeLists.txt | 38 ++ .../DriveModes/ManualMode/ManualMode.cpp | 229 +++++++++++ .../DriveModes/ManualMode/ManualMode.hpp | 137 +++++++ .../DriveModes/OffboardMode/CMakeLists.txt | 38 ++ .../DriveModes/OffboardMode/OffboardMode.cpp | 79 ++++ .../DriveModes/OffboardMode/OffboardMode.hpp | 85 +++++ .../rover_ackermann/RoverAckermann.cpp | 359 +----------------- .../rover_ackermann/RoverAckermann.hpp | 157 +------- 13 files changed, 1052 insertions(+), 505 deletions(-) create mode 100644 src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.cpp create mode 100644 src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.hpp create mode 100644 src/modules/rover_ackermann/DriveModes/AutoMode/CMakeLists.txt create mode 100644 src/modules/rover_ackermann/DriveModes/CMakeLists.txt create mode 100644 src/modules/rover_ackermann/DriveModes/ManualMode/CMakeLists.txt create mode 100644 src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp create mode 100644 src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp create mode 100644 src/modules/rover_ackermann/DriveModes/OffboardMode/CMakeLists.txt create mode 100644 src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.cpp create mode 100644 src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.hpp diff --git a/src/modules/rover_ackermann/CMakeLists.txt b/src/modules/rover_ackermann/CMakeLists.txt index 8f71478554..d2d25280a1 100644 --- a/src/modules/rover_ackermann/CMakeLists.txt +++ b/src/modules/rover_ackermann/CMakeLists.txt @@ -36,6 +36,7 @@ add_subdirectory(AckermannRateControl) add_subdirectory(AckermannAttControl) add_subdirectory(AckermannVelControl) add_subdirectory(AckermannPosControl) +add_subdirectory(DriveModes) px4_add_module( MODULE modules__rover_ackermann @@ -49,6 +50,9 @@ px4_add_module( AckermannAttControl AckermannVelControl AckermannPosControl + AutoMode + ManualMode + OffboardMode px4_work_queue rover_control pure_pursuit diff --git a/src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.cpp b/src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.cpp new file mode 100644 index 0000000000..53ab04dcd9 --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.cpp @@ -0,0 +1,196 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "AutoMode.hpp" + +using namespace time_literals; + +AutoMode::AutoMode(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_position_setpoint_pub.advertise(); +} + +void AutoMode::updateParams() +{ + ModuleParams::updateParams(); + _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; + + if (_param_ra_wheel_base.get() > FLT_EPSILON && _max_yaw_rate > FLT_EPSILON + && _param_ra_max_str_ang.get() > FLT_EPSILON) { + _min_speed = _param_ra_wheel_base.get() * _max_yaw_rate / tanf(_param_ra_max_str_ang.get()); + } +} + +void AutoMode::autoControl() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); + } + + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + + if (!_global_ned_proj_ref.isInitialized() + || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { + _global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, + vehicle_local_position.ref_timestamp); + } + + _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); + } + + if (_position_setpoint_triplet_sub.updated()) { + updateWaypointsAndAcceptanceRadius(); + } + + // Distances to waypoints + const float distance_to_prev_wp = sqrt(powf(_curr_pos_ned(0) - _prev_wp_ned(0), + 2) + powf(_curr_pos_ned(1) - _prev_wp_ned(1), 2)); + const float distance_to_curr_wp = sqrt(powf(_curr_pos_ned(0) - _curr_wp_ned(0), + 2) + powf(_curr_pos_ned(1) - _curr_wp_ned(1), 2)); + + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = _curr_wp_ned(0); + rover_position_setpoint.position_ned[1] = _curr_wp_ned(1); + rover_position_setpoint.start_ned[0] = _prev_wp_ned(0); + rover_position_setpoint.start_ned[1] = _prev_wp_ned(1); + rover_position_setpoint.arrival_speed = arrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius, _curr_wp_type, + _waypoint_transition_angle, _max_yaw_rate); + rover_position_setpoint.cruising_speed = cruisingSpeed(_cruising_speed, _min_speed, distance_to_prev_wp, + distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _waypoint_transition_angle, + _prev_waypoint_transition_angle, _max_yaw_rate); + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); +} + +void AutoMode::updateWaypointsAndAcceptanceRadius() +{ + position_setpoint_triplet_s position_setpoint_triplet{}; + _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); + _curr_wp_type = position_setpoint_triplet.current.type; + + RoverControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet, + _curr_pos_ned, _global_ned_proj_ref); + + _prev_waypoint_transition_angle = _waypoint_transition_angle; + _waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned, _next_wp_ned); + + // Update acceptance radius + _prev_acceptance_radius = _acceptance_radius; + + if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) { + _acceptance_radius = updateAcceptanceRadius(_waypoint_transition_angle, _param_nav_acc_rad.get(), + _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_str_ang.get()); + + } else { + _acceptance_radius = _param_nav_acc_rad.get(); + } + + // Waypoint cruising speed + _cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain( + position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get(); +} + +float AutoMode::updateAcceptanceRadius(const float waypoint_transition_angle, + const float default_acceptance_radius, const float acceptance_radius_gain, + const float acceptance_radius_max, const float wheel_base, const float max_steer_angle) +{ + // Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment + float acceptance_radius = default_acceptance_radius; + + if (PX4_ISFINITE(_waypoint_transition_angle)) { + const float theta = waypoint_transition_angle / 2.f; + const float min_turning_radius = wheel_base / sinf(max_steer_angle); + const float acceptance_radius_temp = min_turning_radius / tanf(theta); + const float acceptance_radius_temp_scaled = acceptance_radius_gain * + acceptance_radius_temp; // Scale geometric ideal acceptance radius to account for kinematic and dynamic effects + acceptance_radius = math::constrain(acceptance_radius_temp_scaled, default_acceptance_radius, + acceptance_radius_max); + } + + // Publish updated acceptance radius + position_controller_status_s pos_ctrl_status{}; + pos_ctrl_status.acceptance_radius = acceptance_radius; + pos_ctrl_status.timestamp = hrt_absolute_time(); + _position_controller_status_pub.publish(pos_ctrl_status); + return acceptance_radius; +} + +float AutoMode::arrivalSpeed(const float cruising_speed, const float miss_speed_min, const float acc_rad, + const int curr_wp_type, const float waypoint_transition_angle, const float max_yaw_rate) +{ + if (!PX4_ISFINITE(waypoint_transition_angle) + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { + return 0.f; // Stop at the waypoint + + } else { + const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); + const float cornering_speed = max_yaw_rate * turning_circle; + return math::constrain(cornering_speed, miss_speed_min, cruising_speed); // Slow down for cornering + } +} + +float AutoMode::cruisingSpeed(const float cruising_speed, const float miss_speed_min, + const float distance_to_prev_wp, const float distance_to_curr_wp, const float acc_rad, const float prev_acc_rad, + const float waypoint_transition_angle, const float prev_waypoint_transition_angle, const float max_yaw_rate) +{ + // Catch improper values + if (miss_speed_min < -FLT_EPSILON || miss_speed_min > cruising_speed) { + return cruising_speed; + } + + // Cornering slow down effect + if (distance_to_prev_wp <= prev_acc_rad && prev_acc_rad > FLT_EPSILON && PX4_ISFINITE(prev_waypoint_transition_angle)) { + const float turning_circle = prev_acc_rad * tanf(prev_waypoint_transition_angle / 2.f); + const float cornering_speed = max_yaw_rate * turning_circle; + return math::constrain(cornering_speed, miss_speed_min, cruising_speed); + + } + + if (distance_to_curr_wp <= acc_rad && acc_rad > FLT_EPSILON && PX4_ISFINITE(waypoint_transition_angle)) { + const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); + const float cornering_speed = max_yaw_rate * turning_circle; + return math::constrain(cornering_speed, miss_speed_min, cruising_speed); + + } + + return cruising_speed; // Fallthrough + +} diff --git a/src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.hpp b/src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.hpp new file mode 100644 index 0000000000..c20a7c006f --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/AutoMode/AutoMode.hpp @@ -0,0 +1,161 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include +#include + +/** + * @brief Class for ackermann auto mode. + */ +class AutoMode : public ModuleParams +{ +public: + /** + * @brief Constructor for auto mode. + * @param parent The parent ModuleParams object. + */ + AutoMode(ModuleParams *parent); + ~AutoMode() = default; + + /** + * @brief Generate and publish roverPositionSetpoint from positionSetpointTriplet. + */ + void autoControl(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + /** + * @brief Update global/NED waypoint coordinates and acceptance radius. + */ + void updateWaypointsAndAcceptanceRadius(); + + /** + * @brief Publish the acceptance radius for current waypoint based on the angle between a line segment + * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of the vehicle. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param default_acceptance_radius Default acceptance radius for waypoints [m]. + * @param acceptance_radius_gain Tuning parameter that scales the geometric optimal acceptance radius for the corner cutting [-]. + * @param acceptance_radius_max Maximum value for the acceptance radius [m]. + * @param wheel_base Rover wheelbase [m]. + * @param max_steer_angle Rover maximum steer angle [rad]. + * @return Updated acceptance radius [m]. + */ + float updateAcceptanceRadius(float waypoint_transition_angle, float default_acceptance_radius, + float acceptance_radius_gain, float acceptance_radius_max, float wheel_base, float max_steer_angle); + + /** + * @brief Calculate the speed at which the rover should arrive at the current waypoint based on the upcoming corner. + * @param cruising_speed Cruising speed [m/s]. + * @param miss_speed_min Minimum speed setpoint [m/s]. + * @param acc_rad Acceptance radius of the current waypoint [m]. + * @param curr_wp_type Type of the current waypoint. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] + * @return Speed setpoint [m/s]. + */ + float arrivalSpeed(float cruising_speed, float miss_speed_min, float acc_rad, int curr_wp_type, + float waypoint_transition_angle, float max_yaw_rate); + + /** + * @brief Calculate the cruising speed setpoint. During cornering the speed is restricted based on the radius of the corner. + * @param cruising_speed Cruising speed [m/s]. + * @param miss_speed_min Minimum speed setpoint [m/s]. + * @param distance_to_prev_wp Distance to the previous waypoint [m]. + * @param distance_to_curr_wp Distance to the current waypoint [m]. + * @param acc_rad Acceptance radius of the current waypoint [m]. + * @param prev_acc_rad Acceptance radius of the previous waypoint [m]. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param prev_waypoint_transition_angle Previous angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] + * @return Speed setpoint [m/s]. + */ + float cruisingSpeed(float cruising_speed, float miss_speed_min, float distance_to_prev_wp, + float distance_to_curr_wp, float acc_rad, float prev_acc_rad, float waypoint_transition_angle, + float prev_waypoint_transition_angle, float max_yaw_rate); + + // uORB subscriptions + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; + + // uORB publications + uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; + uORB::Publication _position_controller_status_pub{ORB_ID(position_controller_status)}; + + // Variables + MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates + Quatf _vehicle_attitude_quaternion{}; + Vector2f _curr_wp_ned{NAN, NAN}; + Vector2f _prev_wp_ned{NAN, NAN}; + Vector2f _next_wp_ned{NAN, NAN}; + Vector2f _curr_pos_ned{NAN, NAN}; + float _acceptance_radius{0.5f}; + float _prev_acceptance_radius{0.5f}; + float _cruising_speed{0.f}; + float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + float _prev_waypoint_transition_angle{0.f}; // Previous Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + float _max_yaw_rate{NAN}; + float _vehicle_yaw{NAN}; + float _min_speed{NAN}; // Speed at which the maximum yaw rate limit is enforced given the maximum steer angle and wheel base. + int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_ro_yaw_rate_limit, + (ParamFloat) _param_ro_speed_limit, + (ParamFloat) _param_ra_wheel_base, + (ParamFloat) _param_ra_max_str_ang, + (ParamFloat) _param_nav_acc_rad, + (ParamFloat) _param_ra_acc_rad_max, + (ParamFloat) _param_ra_acc_rad_gain + ) +}; diff --git a/src/modules/rover_ackermann/DriveModes/AutoMode/CMakeLists.txt b/src/modules/rover_ackermann/DriveModes/AutoMode/CMakeLists.txt new file mode 100644 index 0000000000..6f68333be1 --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/AutoMode/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(AutoMode + AutoMode.cpp +) + +target_include_directories(AutoMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_ackermann/DriveModes/CMakeLists.txt b/src/modules/rover_ackermann/DriveModes/CMakeLists.txt new file mode 100644 index 0000000000..1918b9644e --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(AutoMode) +add_subdirectory(ManualMode) +add_subdirectory(OffboardMode) diff --git a/src/modules/rover_ackermann/DriveModes/ManualMode/CMakeLists.txt b/src/modules/rover_ackermann/DriveModes/ManualMode/CMakeLists.txt new file mode 100644 index 0000000000..827489ad9f --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/ManualMode/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(ManualMode + ManualMode.cpp +) + +target_include_directories(ManualMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp new file mode 100644 index 0000000000..f2810f06f4 --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp @@ -0,0 +1,229 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "ManualMode.hpp" + +using namespace time_literals; + +ManualMode::ManualMode(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_throttle_setpoint_pub.advertise(); + _rover_steering_setpoint_pub.advertise(); + _rover_rate_setpoint_pub.advertise(); + _rover_attitude_setpoint_pub.advertise(); + _rover_velocity_setpoint_pub.advertise(); + _rover_position_setpoint_pub.advertise(); +} + +void ManualMode::updateParams() +{ + ModuleParams::updateParams(); + _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; +} + +void ManualMode::manualControl(const int nav_state) +{ + switch (nav_state) { + case vehicle_status_s::NAVIGATION_STATE_MANUAL: + manual(); + break; + + case vehicle_status_s::NAVIGATION_STATE_ACRO: + acro(); + break; + + case vehicle_status_s::NAVIGATION_STATE_STAB: + stab(); + break; + + case vehicle_status_s::NAVIGATION_STATE_POSCTL: + position(); + break; + } +} + +void ManualMode::manual() +{ + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = hrt_absolute_time(); + rover_steering_setpoint.normalized_steering_angle = manual_control_setpoint.roll; + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); +} + +void ManualMode::acro() +{ + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * math::interpolate + (manual_control_setpoint.roll, -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); +} + +void ManualMode::stab() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); + } + + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); + + const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), + _max_yaw_rate / _param_ro_yaw_p.get()); + + if (fabsf(yaw_delta) > FLT_EPSILON + || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { // Closed loop yaw rate control + _stab_yaw_setpoint = NAN; + const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + matrix::sign(manual_control_setpoint.throttle) * yaw_delta); + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = yaw_setpoint; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + + } else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw) + if (!PX4_ISFINITE(_stab_yaw_setpoint)) { + _stab_yaw_setpoint = _vehicle_yaw; + } + + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + } +} + +void ManualMode::position() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); + } + + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + + if (!_global_ned_proj_ref.isInitialized() + || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { + _global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, + vehicle_local_position.ref_timestamp); + } + + _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); + } + + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + + const float speed_setpoint = math::interpolate(manual_control_setpoint.throttle, + -1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); + const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), + _max_yaw_rate / _param_ro_yaw_p.get()); + + if (fabsf(yaw_delta) > FLT_EPSILON + || fabsf(speed_setpoint) < FLT_EPSILON) { // Closed loop yaw rate control + _pos_ctl_course_direction = Vector2f(NAN, NAN); + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover + const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + sign(speed_setpoint) * yaw_delta); + const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); + const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * + pos_ctl_course_direction; + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + + } else { // Course control if the steering input is zero (keep driving on a straight line) + if (!_pos_ctl_course_direction.isAllFinite()) { + _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); + _pos_ctl_start_position_ned = _curr_pos_ned; + } + + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover + const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned; + const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); + const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * + vector_scaling * _pos_ctl_course_direction; + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); + rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + } +} + +void ManualMode::reset() +{ + _stab_yaw_setpoint = NAN; + _pos_ctl_course_direction = Vector2f(NAN, NAN); + _pos_ctl_start_position_ned = Vector2f(NAN, NAN); + _curr_pos_ned = Vector2f(NAN, NAN); +} diff --git a/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp new file mode 100644 index 0000000000..8079b326ac --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp @@ -0,0 +1,137 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/** + * @brief Class for ackermann manual mode. + */ +class ManualMode : public ModuleParams +{ +public: + /** + * @brief Constructor for ManualMode. + * @param parent The parent ModuleParams object. + */ + ManualMode(ModuleParams *parent); + ~ManualMode() = default; + + /** + * @brief Generate and publish roverSetpoints from manualControlSetpoints. + */ + void manualControl(int nav_state); + + /** + * @brief Reset manual mode variables. + */ + void reset(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + /** + * @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint. + */ + void manual(); + + /** + * @brief Generate and publish roverThrottleSetpoint and RoverRateSetpoint from manualControlSetpoint. + */ + void acro(); + + /** + * @brief Generate and publish roverThrottleSetpoint and RoverAttitudeSetpoint from manualControlSetpoint. + */ + void stab(); + + /** + * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint. + */ + void position(); + + // uORB subscriptions + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + + // uORB publications + uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; + uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; + uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; + uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; + uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; + uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; + + // Variables + MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates + Quatf _vehicle_attitude_quaternion{}; + Vector2f _pos_ctl_course_direction{NAN, NAN}; + Vector2f _pos_ctl_start_position_ned{NAN, NAN}; + Vector2f _curr_pos_ned{NAN, NAN}; + float _stab_yaw_setpoint{NAN}; + float _vehicle_yaw{NAN}; + float _max_yaw_rate{NAN}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_ro_yaw_rate_limit, + (ParamFloat) _param_ro_yaw_p, + (ParamFloat) _param_ro_yaw_stick_dz, + (ParamFloat) _param_pp_lookahd_max, + (ParamFloat) _param_ro_speed_limit + ) +}; diff --git a/src/modules/rover_ackermann/DriveModes/OffboardMode/CMakeLists.txt b/src/modules/rover_ackermann/DriveModes/OffboardMode/CMakeLists.txt new file mode 100644 index 0000000000..a73b2dedd8 --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/OffboardMode/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(OffboardMode + OffboardMode.cpp +) + +target_include_directories(OffboardMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.cpp b/src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.cpp new file mode 100644 index 0000000000..dfd12cddb0 --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.cpp @@ -0,0 +1,79 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "OffboardMode.hpp" + +using namespace time_literals; + +OffboardMode::OffboardMode(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_velocity_setpoint_pub.advertise(); + _rover_position_setpoint_pub.advertise(); +} + +void OffboardMode::updateParams() +{ + ModuleParams::updateParams(); +} + +void OffboardMode::offboardControl() +{ + offboard_control_mode_s offboard_control_mode{}; + _offboard_control_mode_sub.copy(&offboard_control_mode); + + trajectory_setpoint_s trajectory_setpoint{}; + _trajectory_setpoint_sub.copy(&trajectory_setpoint); + + if (offboard_control_mode.position) { + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; + rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.cruising_speed = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + + } else if (offboard_control_mode.velocity) { + const Vector2f velocity_ned(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]); + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = hrt_absolute_time(); + rover_velocity_setpoint.speed = velocity_ned.norm(); + rover_velocity_setpoint.bearing = atan2f(velocity_ned(1), velocity_ned(0)); + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + } +} diff --git a/src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.hpp b/src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.hpp new file mode 100644 index 0000000000..331df5e907 --- /dev/null +++ b/src/modules/rover_ackermann/DriveModes/OffboardMode/OffboardMode.hpp @@ -0,0 +1,85 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include + +using namespace matrix; + +/** + * @brief Class for ackermann manual mode. + */ +class OffboardMode : public ModuleParams +{ +public: + /** + * @brief Constructor for OffboardMode. + * @param parent The parent ModuleParams object. + */ + OffboardMode(ModuleParams *parent); + ~OffboardMode() = default; + + /** + * @brief Generate and publish roverSetpoints from trajectorySetpoint. + */ + void offboardControl(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + // uORB subscriptions + uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; + uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; + + // uORB publications + uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; + uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; +}; diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index fcc0f059c6..236ecb6af2 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -51,12 +51,6 @@ bool RoverAckermann::init() void RoverAckermann::updateParams() { ModuleParams::updateParams(); - _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; - - if (_param_ra_wheel_base.get() > FLT_EPSILON && _max_yaw_rate > FLT_EPSILON - && _param_ra_max_str_ang.get() > FLT_EPSILON) { - _min_speed = _param_ra_wheel_base.get() * _max_yaw_rate / tanf(_param_ra_max_str_ang.get()); - } } void RoverAckermann::Run() @@ -99,13 +93,13 @@ void RoverAckermann::Run() if (_vehicle_control_mode.flag_armed && _sanity_checks_passed) { // Generate setpoints if (_vehicle_control_mode.flag_control_manual_enabled) { - manualControl(); + _manual_mode.manualControl(_nav_state); } else if (_vehicle_control_mode.flag_control_auto_enabled) { - autoPositionMode(); + _auto_mode.autoControl(); } else if (_vehicle_control_mode.flag_control_offboard_enabled) { - offboardControl(); + _offboard_mode.offboardControl(); } updateControllers(); @@ -118,348 +112,6 @@ void RoverAckermann::Run() } -void RoverAckermann::manualControl() -{ - switch (_nav_state) { - case vehicle_status_s::NAVIGATION_STATE_MANUAL: - manualManualMode(); - break; - - case vehicle_status_s::NAVIGATION_STATE_ACRO: - manualAcroMode(); - break; - - case vehicle_status_s::NAVIGATION_STATE_STAB: - manualStabMode(); - break; - - case vehicle_status_s::NAVIGATION_STATE_POSCTL: - manualPositionMode(); - break; - } -} - -void RoverAckermann::manualManualMode() -{ - manual_control_setpoint_s manual_control_setpoint{}; - _manual_control_setpoint_sub.copy(&manual_control_setpoint); - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = hrt_absolute_time(); - rover_steering_setpoint.normalized_steering_angle = manual_control_setpoint.roll; - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = hrt_absolute_time(); - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); -} - -void RoverAckermann::manualAcroMode() -{ - manual_control_setpoint_s manual_control_setpoint{}; - _manual_control_setpoint_sub.copy(&manual_control_setpoint); - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = hrt_absolute_time(); - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - rover_rate_setpoint_s rover_rate_setpoint{}; - rover_rate_setpoint.timestamp = hrt_absolute_time(); - rover_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * math::interpolate - (manual_control_setpoint.roll, -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); - _rover_rate_setpoint_pub.publish(rover_rate_setpoint); -} - -void RoverAckermann::manualStabMode() -{ - if (_vehicle_attitude_sub.updated()) { - vehicle_attitude_s vehicle_attitude{}; - _vehicle_attitude_sub.copy(&vehicle_attitude); - _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); - _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); - } - - manual_control_setpoint_s manual_control_setpoint{}; - _manual_control_setpoint_sub.copy(&manual_control_setpoint); - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = hrt_absolute_time(); - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - - const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), - _max_yaw_rate / _param_ro_yaw_p.get()); - - if (fabsf(yaw_delta) > FLT_EPSILON - || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { // Closed loop yaw rate control - _stab_yaw_setpoint = NAN; - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + matrix::sign(manual_control_setpoint.throttle) * yaw_delta); - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = hrt_absolute_time(); - rover_attitude_setpoint.yaw_setpoint = yaw_setpoint; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - - } else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw) - if (!PX4_ISFINITE(_stab_yaw_setpoint)) { - _stab_yaw_setpoint = _vehicle_yaw; - } - - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = hrt_absolute_time(); - rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } -} - -void RoverAckermann::manualPositionMode() -{ - if (_vehicle_attitude_sub.updated()) { - vehicle_attitude_s vehicle_attitude{}; - _vehicle_attitude_sub.copy(&vehicle_attitude); - _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); - _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); - } - - if (_vehicle_local_position_sub.updated()) { - vehicle_local_position_s vehicle_local_position{}; - _vehicle_local_position_sub.copy(&vehicle_local_position); - - if (!_global_ned_proj_ref.isInitialized() - || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { - _global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, - vehicle_local_position.ref_timestamp); - } - - _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); - } - - manual_control_setpoint_s manual_control_setpoint{}; - _manual_control_setpoint_sub.copy(&manual_control_setpoint); - - const float speed_setpoint = math::interpolate(manual_control_setpoint.throttle, - -1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); - const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), - _max_yaw_rate / _param_ro_yaw_p.get()); - - if (fabsf(yaw_delta) > FLT_EPSILON - || fabsf(speed_setpoint) < FLT_EPSILON) { // Closed loop yaw rate control - _pos_ctl_course_direction = Vector2f(NAN, NAN); - // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + sign(speed_setpoint) * yaw_delta); - const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); - const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * - pos_ctl_course_direction; - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); - rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); - rover_position_setpoint.start_ned[0] = NAN; - rover_position_setpoint.start_ned[1] = NAN; - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.cruising_speed = speed_setpoint; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - - } else { // Course control if the steering input is zero (keep driving on a straight line) - if (!_pos_ctl_course_direction.isAllFinite()) { - _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); - _pos_ctl_start_position_ned = _curr_pos_ned; - } - - // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover - const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned; - const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); - const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * - vector_scaling * _pos_ctl_course_direction; - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); - rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); - rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); - rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.cruising_speed = speed_setpoint; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - } -} - -void RoverAckermann::autoPositionMode() -{ - if (_vehicle_attitude_sub.updated()) { - vehicle_attitude_s vehicle_attitude{}; - _vehicle_attitude_sub.copy(&vehicle_attitude); - _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); - _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); - } - - if (_vehicle_local_position_sub.updated()) { - vehicle_local_position_s vehicle_local_position{}; - _vehicle_local_position_sub.copy(&vehicle_local_position); - - if (!_global_ned_proj_ref.isInitialized() - || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { - _global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, - vehicle_local_position.ref_timestamp); - } - - _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); - } - - if (_position_setpoint_triplet_sub.updated()) { - autoUpdateWaypointsAndAcceptanceRadius(); - } - - // Distances to waypoints - const float distance_to_prev_wp = sqrt(powf(_curr_pos_ned(0) - _prev_wp_ned(0), - 2) + powf(_curr_pos_ned(1) - _prev_wp_ned(1), 2)); - const float distance_to_curr_wp = sqrt(powf(_curr_pos_ned(0) - _curr_wp_ned(0), - 2) + powf(_curr_pos_ned(1) - _curr_wp_ned(1), 2)); - - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = _curr_wp_ned(0); - rover_position_setpoint.position_ned[1] = _curr_wp_ned(1); - rover_position_setpoint.start_ned[0] = _prev_wp_ned(0); - rover_position_setpoint.start_ned[1] = _prev_wp_ned(1); - rover_position_setpoint.arrival_speed = autoArrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius, _curr_wp_type, - _waypoint_transition_angle, _max_yaw_rate); - rover_position_setpoint.cruising_speed = autoCruisingSpeed(_cruising_speed, _min_speed, distance_to_prev_wp, - distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _waypoint_transition_angle, - _prev_waypoint_transition_angle, _max_yaw_rate); - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); -} - -void RoverAckermann::autoUpdateWaypointsAndAcceptanceRadius() -{ - position_setpoint_triplet_s position_setpoint_triplet{}; - _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); - _curr_wp_type = position_setpoint_triplet.current.type; - - RoverControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet, - _curr_pos_ned, _global_ned_proj_ref); - - _prev_waypoint_transition_angle = _waypoint_transition_angle; - _waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned, _next_wp_ned); - - // Update acceptance radius - _prev_acceptance_radius = _acceptance_radius; - - if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) { - _acceptance_radius = autoUpdateAcceptanceRadius(_waypoint_transition_angle, _param_nav_acc_rad.get(), - _param_ra_acc_rad_gain.get(), _param_ra_acc_rad_max.get(), _param_ra_wheel_base.get(), _param_ra_max_str_ang.get()); - - } else { - _acceptance_radius = _param_nav_acc_rad.get(); - } - - // Waypoint cruising speed - _cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain( - position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get(); -} - -float RoverAckermann::autoUpdateAcceptanceRadius(const float waypoint_transition_angle, - const float default_acceptance_radius, const float acceptance_radius_gain, - const float acceptance_radius_max, const float wheel_base, const float max_steer_angle) -{ - // Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment - float acceptance_radius = default_acceptance_radius; - - if (PX4_ISFINITE(_waypoint_transition_angle)) { - const float theta = waypoint_transition_angle / 2.f; - const float min_turning_radius = wheel_base / sinf(max_steer_angle); - const float acceptance_radius_temp = min_turning_radius / tanf(theta); - const float acceptance_radius_temp_scaled = acceptance_radius_gain * - acceptance_radius_temp; // Scale geometric ideal acceptance radius to account for kinematic and dynamic effects - acceptance_radius = math::constrain(acceptance_radius_temp_scaled, default_acceptance_radius, - acceptance_radius_max); - } - - // Publish updated acceptance radius - position_controller_status_s pos_ctrl_status{}; - pos_ctrl_status.acceptance_radius = acceptance_radius; - pos_ctrl_status.timestamp = hrt_absolute_time(); - _position_controller_status_pub.publish(pos_ctrl_status); - return acceptance_radius; -} - -float RoverAckermann::autoArrivalSpeed(const float cruising_speed, const float miss_speed_min, const float acc_rad, - const int curr_wp_type, const float waypoint_transition_angle, const float max_yaw_rate) -{ - if (!PX4_ISFINITE(waypoint_transition_angle) - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { - return 0.f; // Stop at the waypoint - - } else { - const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); - const float cornering_speed = max_yaw_rate * turning_circle; - return math::constrain(cornering_speed, miss_speed_min, cruising_speed); // Slow down for cornering - } -} - -float RoverAckermann::autoCruisingSpeed(const float cruising_speed, const float miss_speed_min, - const float distance_to_prev_wp, const float distance_to_curr_wp, const float acc_rad, const float prev_acc_rad, - const float waypoint_transition_angle, const float prev_waypoint_transition_angle, const float max_yaw_rate) -{ - // Catch improper values - if (miss_speed_min < -FLT_EPSILON || miss_speed_min > cruising_speed) { - return cruising_speed; - } - - // Cornering slow down effect - if (distance_to_prev_wp <= prev_acc_rad && prev_acc_rad > FLT_EPSILON && PX4_ISFINITE(prev_waypoint_transition_angle)) { - const float turning_circle = prev_acc_rad * tanf(prev_waypoint_transition_angle / 2.f); - const float cornering_speed = max_yaw_rate * turning_circle; - return math::constrain(cornering_speed, miss_speed_min, cruising_speed); - - } - - if (distance_to_curr_wp <= acc_rad && acc_rad > FLT_EPSILON && PX4_ISFINITE(waypoint_transition_angle)) { - const float turning_circle = acc_rad * tanf(waypoint_transition_angle / 2.f); - const float cornering_speed = max_yaw_rate * turning_circle; - return math::constrain(cornering_speed, miss_speed_min, cruising_speed); - - } - - return cruising_speed; // Fallthrough - -} - -void RoverAckermann::offboardControl() -{ - offboard_control_mode_s offboard_control_mode{}; - _offboard_control_mode_sub.copy(&offboard_control_mode); - - trajectory_setpoint_s trajectory_setpoint{}; - _trajectory_setpoint_sub.copy(&trajectory_setpoint); - - if (offboard_control_mode.position) { - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; - rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; - rover_position_setpoint.start_ned[0] = NAN; - rover_position_setpoint.start_ned[1] = NAN; - rover_position_setpoint.cruising_speed = NAN; - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - - } else if (offboard_control_mode.velocity) { - const Vector2f velocity_ned(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = hrt_absolute_time(); - rover_velocity_setpoint.speed = velocity_ned.norm(); - rover_velocity_setpoint.bearing = atan2f(velocity_ned(1), velocity_ned(0)); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } -} - void RoverAckermann::updateControllers() { if (_vehicle_control_mode.flag_control_position_enabled) { @@ -513,10 +165,7 @@ void RoverAckermann::reset() _ackermann_vel_control.reset(); _ackermann_att_control.reset(); _ackermann_rate_control.reset(); - _stab_yaw_setpoint = NAN; - _pos_ctl_course_direction = Vector2f(NAN, NAN); - _pos_ctl_start_position_ned = Vector2f(NAN, NAN); - _curr_pos_ned = Vector2f(NAN, NAN); + _manual_mode.reset(); } int RoverAckermann::task_spawn(int argc, char *argv[]) diff --git a/src/modules/rover_ackermann/RoverAckermann.hpp b/src/modules/rover_ackermann/RoverAckermann.hpp index 968f99ed4f..c9f8370afa 100644 --- a/src/modules/rover_ackermann/RoverAckermann.hpp +++ b/src/modules/rover_ackermann/RoverAckermann.hpp @@ -42,28 +42,13 @@ // Library includes #include -#include // uORB includes #include #include -#include #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include // Local includes #include "AckermannActControl/AckermannActControl.hpp" @@ -71,6 +56,9 @@ #include "AckermannAttControl/AckermannAttControl.hpp" #include "AckermannVelControl/AckermannVelControl.hpp" #include "AckermannPosControl/AckermannPosControl.hpp" +#include "DriveModes/AutoMode/AutoMode.hpp" +#include "DriveModes/ManualMode/ManualMode.hpp" +#include "DriveModes/OffboardMode/OffboardMode.hpp" class RoverAckermann : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem @@ -103,91 +91,7 @@ private: void Run() override; /** - * @brief Handle manual control - */ - void manualControl(); - - /** - * @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint. - */ - void manualManualMode(); - - /** - * @brief Generate and publish roverThrottleSetpoint and RoverRateSetpoint from manualControlSetpoint. - */ - void manualAcroMode(); - - /** - * @brief Generate and publish roverThrottleSetpoint and RoverAttitudeSetpoint from manualControlSetpoint. - */ - void manualStabMode(); - - /** - * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint. - */ - void manualPositionMode(); - - /** - * @brief Generate and publish roverVelocitySetpoint from positionSetpointTriplet. - */ - void autoPositionMode(); - - /** - * @brief Update global/NED waypoint coordinates and acceptance radius. - */ - void autoUpdateWaypointsAndAcceptanceRadius(); - - /** - * @brief Publish the acceptance radius for current waypoint based on the angle between a line segment - * from the previous to the current waypoint/current to the next waypoint and maximum steer angle of the vehicle. - * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param default_acceptance_radius Default acceptance radius for waypoints [m]. - * @param acceptance_radius_gain Tuning parameter that scales the geometric optimal acceptance radius for the corner cutting [-]. - * @param acceptance_radius_max Maximum value for the acceptance radius [m]. - * @param wheel_base Rover wheelbase [m]. - * @param max_steer_angle Rover maximum steer angle [rad]. - * @return Updated acceptance radius [m]. - */ - float autoUpdateAcceptanceRadius(float waypoint_transition_angle, float default_acceptance_radius, - float acceptance_radius_gain, float acceptance_radius_max, float wheel_base, float max_steer_angle); - - /** - * @brief Calculate the speed at which the rover should arrive at the current waypoint based on the upcoming corner. - * @param cruising_speed Cruising speed [m/s]. - * @param miss_speed_min Minimum speed setpoint [m/s]. - * @param acc_rad Acceptance radius of the current waypoint [m]. - * @param curr_wp_type Type of the current waypoint. - * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] - * @return Speed setpoint [m/s]. - */ - float autoArrivalSpeed(float cruising_speed, float miss_speed_min, float acc_rad, int curr_wp_type, - float waypoint_transition_angle, float max_yaw_rate); - - /** - * @brief Calculate the cruising speed setpoint. During cornering the speed is restricted based on the radius of the corner. - * @param cruising_speed Cruising speed [m/s]. - * @param miss_speed_min Minimum speed setpoint [m/s]. - * @param distance_to_prev_wp Distance to the previous waypoint [m]. - * @param distance_to_curr_wp Distance to the current waypoint [m]. - * @param acc_rad Acceptance radius of the current waypoint [m]. - * @param prev_acc_rad Acceptance radius of the previous waypoint [m]. - * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param prev_waypoint_transition_angle Previous angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param max_yaw_rate Maximum yaw rate setpoint [rad/s] - * @return Speed setpoint [m/s]. - */ - float autoCruisingSpeed(float cruising_speed, float miss_speed_min, float distance_to_prev_wp, - float distance_to_curr_wp, float acc_rad, float prev_acc_rad, float waypoint_transition_angle, - float prev_waypoint_transition_angle, float max_yaw_rate); - - /** - * @brief Translate trajectorySetpoint to roverSetpoints and publish them - */ - void offboardControl(); - - /** - * @brief Update the controllers + * @brief Update the active controllers. */ void updateControllers(); @@ -206,70 +110,23 @@ private: void reset(); // uORB subscriptions - uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; - uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; - uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; vehicle_control_mode_s _vehicle_control_mode{}; - // uORB publications - uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; - uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; - uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; - uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; - uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; - uORB::Publication _position_controller_status_pub{ORB_ID(position_controller_status)}; - // Class instances AckermannActControl _ackermann_act_control{this}; AckermannRateControl _ackermann_rate_control{this}; AckermannAttControl _ackermann_att_control{this}; AckermannVelControl _ackermann_vel_control{this}; AckermannPosControl _ackermann_pos_control{this}; + AutoMode _auto_mode{this}; + ManualMode _manual_mode{this}; + OffboardMode _offboard_mode{this}; // Variables - MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates - Quatf _vehicle_attitude_quaternion{}; - float _max_yaw_rate{NAN}; - float _vehicle_yaw{NAN}; - float _min_speed{0.f}; // Speed at which the maximum yaw rate limit is enforced given the maximum steer angle and wheel base. int _nav_state{0}; // Navigation state of the vehicle bool _sanity_checks_passed{true}; // True if checks for all active controllers pass bool _was_armed{false}; // True if the vehicle was armed before the last reset - - // Auto Mode Variables - Vector2f _curr_wp_ned{}; - Vector2f _prev_wp_ned{}; - Vector2f _next_wp_ned{}; - float _acceptance_radius{0.5f}; - float _prev_acceptance_radius{0.5f}; - float _cruising_speed{0.f}; - float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - float _prev_waypoint_transition_angle{0.f}; // Previous Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE}; - - // Manual Mode Variables - Vector2f _pos_ctl_course_direction{NAN, NAN}; - Vector2f _pos_ctl_start_position_ned{NAN, NAN}; - Vector2f _curr_pos_ned{NAN, NAN}; - float _stab_yaw_setpoint{NAN}; - - DEFINE_PARAMETERS( - (ParamFloat) _param_ro_yaw_rate_limit, - (ParamFloat) _param_ro_yaw_p, - (ParamFloat) _param_ro_yaw_stick_dz, - (ParamFloat) _param_pp_lookahd_max, - (ParamFloat) _param_ro_speed_limit, - (ParamFloat) _param_ra_wheel_base, - (ParamFloat) _param_ra_max_str_ang, - (ParamFloat) _param_nav_acc_rad, - (ParamFloat) _param_ra_acc_rad_max, - (ParamFloat) _param_ra_acc_rad_gain - ) }; From 0d9cb1f0481b3166137c40d6713ae5dd3686e3df Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Mon, 19 May 2025 16:00:51 +0200 Subject: [PATCH 048/130] ackermann: only control relevant setpoints in manual modes --- .../AckermannActControl.cpp | 14 --- .../AckermannAttControl.cpp | 5 -- .../AckermannPosControl.cpp | 78 ++++++++--------- .../AckermannRateControl.cpp | 72 ++++++++-------- .../AckermannVelControl.cpp | 6 -- .../DriveModes/ManualMode/ManualMode.cpp | 85 +++++++++---------- .../DriveModes/ManualMode/ManualMode.hpp | 29 +++---- .../rover_ackermann/RoverAckermann.cpp | 46 ++++++---- .../rover_ackermann/RoverAckermann.hpp | 8 +- 9 files changed, 165 insertions(+), 178 deletions(-) diff --git a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp index 4022464167..b448d09396 100644 --- a/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp +++ b/src/modules/rover_ackermann/AckermannActControl/AckermannActControl.cpp @@ -77,12 +77,6 @@ void AckermannActControl::updateActControl() actuator_motors.timestamp = _timestamp; _actuator_motors_pub.publish(actuator_motors); - } else { - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); - actuator_motors.control[0] = 0.f; - actuator_motors.timestamp = _timestamp; - _actuator_motors_pub.publish(actuator_motors); } // Servo control @@ -114,15 +108,7 @@ void AckermannActControl::updateActControl() actuator_servos.control[0] = _servo_setpoint.getState(); actuator_servos.timestamp = _timestamp; _actuator_servos_pub.publish(actuator_servos); - - } else { - actuator_servos_s actuator_servos{}; - actuator_servos.control[0] = 0.f; - actuator_servos.timestamp = _timestamp; - _actuator_servos_pub.publish(actuator_servos); } - - } void AckermannActControl::stopVehicle() diff --git a/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp b/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp index a866390316..55f4e733c3 100644 --- a/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp +++ b/src/modules/rover_ackermann/AckermannAttControl/AckermannAttControl.cpp @@ -81,11 +81,6 @@ void AckermannAttControl::updateAttControl() rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate); _rover_rate_setpoint_pub.publish(rover_rate_setpoint); - } else { - rover_rate_setpoint_s rover_rate_setpoint{}; - rover_rate_setpoint.timestamp = _timestamp; - rover_rate_setpoint.yaw_rate_setpoint = 0.f; - _rover_rate_setpoint_pub.publish(rover_rate_setpoint); } // Publish attitude controller status (logging only) diff --git a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp index a2b5ec0e01..026406c57d 100644 --- a/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp +++ b/src/modules/rover_ackermann/AckermannPosControl/AckermannPosControl.cpp @@ -57,53 +57,49 @@ void AckermannPosControl::updatePosControl() hrt_abstime timestamp = hrt_absolute_time(); const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]); - float distance_to_target = target_waypoint_ned.isAllFinite() ? (target_waypoint_ned - _curr_pos_ned).norm() : NAN; - if (PX4_ISFINITE(distance_to_target) && distance_to_target > _acceptance_radius) { + if (target_waypoint_ned.isAllFinite()) { + float distance_to_target = (target_waypoint_ned - _curr_pos_ned).norm(); - float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : - 0.f; - const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _acceptance_radius : distance_to_target; - float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), - _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); - speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); + if (distance_to_target > _acceptance_radius) { + float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : + 0.f; + const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _acceptance_radius : distance_to_target; + float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), + _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); + speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); - if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { - speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, - fabsf(_rover_position_setpoint.cruising_speed)); + if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { + speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, + fabsf(_rover_position_setpoint.cruising_speed)); + } + + pure_pursuit_status_s pure_pursuit_status{}; + pure_pursuit_status.timestamp = timestamp; + + const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), + _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, + _curr_pos_ned, fabsf(speed_setpoint)); + _pure_pursuit_status_pub.publish(pure_pursuit_status); + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = timestamp; + rover_velocity_setpoint.speed = speed_setpoint; + rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi( + bearing_setpoint + M_PI_F); + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + } else { + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = timestamp; + rover_velocity_setpoint.speed = 0.f; + rover_velocity_setpoint.bearing = _vehicle_yaw; + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); } - - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = timestamp; - - const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, - _curr_pos_ned, fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi( - bearing_setpoint + M_PI_F); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } else { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = timestamp; - rover_velocity_setpoint.speed = 0.f; - rover_velocity_setpoint.bearing = _vehicle_yaw; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); } } void AckermannPosControl::updateSubscriptions() { - if (_rover_position_setpoint_sub.updated()) { - _rover_position_setpoint_sub.copy(&_rover_position_setpoint); - _start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]); - _start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned; - } - if (_position_controller_status_sub.updated()) { position_controller_status_s position_controller_status{}; _position_controller_status_sub.copy(&position_controller_status); @@ -130,6 +126,12 @@ void AckermannPosControl::updateSubscriptions() _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); } + if (_rover_position_setpoint_sub.updated()) { + _rover_position_setpoint_sub.copy(&_rover_position_setpoint); + _start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]); + _start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned; + } + } bool AckermannPosControl::runSanityChecks() diff --git a/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp b/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp index 3c74a3ea48..30cb26510b 100644 --- a/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp +++ b/src/modules/rover_ackermann/AckermannRateControl/AckermannRateControl.cpp @@ -64,47 +64,49 @@ void AckermannRateControl::updateRateControl() _timestamp = hrt_absolute_time(); const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - if (fabsf(_estimated_speed) > FLT_EPSILON && PX4_ISFINITE(_yaw_rate_setpoint)) { - // Set up feasible yaw rate setpoint - float steering_setpoint{0.f}; - float max_possible_yaw_rate = fabsf(_estimated_speed) * tanf(_param_ra_max_str_ang.get()) / - _param_ra_wheel_base.get(); // Maximum possible yaw rate at current velocity - float yaw_rate_limit = math::min(max_possible_yaw_rate, _max_yaw_rate); - float constrained_yaw_rate = math::constrain(_yaw_rate_setpoint, -yaw_rate_limit, yaw_rate_limit); + if (PX4_ISFINITE(_yaw_rate_setpoint)) { + if (fabsf(_estimated_speed) > FLT_EPSILON) { + // Set up feasible yaw rate setpoint + float steering_setpoint{0.f}; + float max_possible_yaw_rate = fabsf(_estimated_speed) * tanf(_param_ra_max_str_ang.get()) / + _param_ra_wheel_base.get(); // Maximum possible yaw rate at current velocity + float yaw_rate_limit = math::min(max_possible_yaw_rate, _max_yaw_rate); + float constrained_yaw_rate = math::constrain(_yaw_rate_setpoint, -yaw_rate_limit, yaw_rate_limit); - if (_param_ro_yaw_accel_limit.get() > FLT_EPSILON) { // Apply slew rate if configured - if (fabsf(_adjusted_yaw_rate_setpoint.getState() - _vehicle_yaw_rate) > fabsf(constrained_yaw_rate - - _vehicle_yaw_rate)) { - _adjusted_yaw_rate_setpoint.setForcedValue(_vehicle_yaw_rate); + if (_param_ro_yaw_accel_limit.get() > FLT_EPSILON) { // Apply slew rate if configured + if (fabsf(_adjusted_yaw_rate_setpoint.getState() - _vehicle_yaw_rate) > fabsf(constrained_yaw_rate - + _vehicle_yaw_rate)) { + _adjusted_yaw_rate_setpoint.setForcedValue(_vehicle_yaw_rate); + } + + _adjusted_yaw_rate_setpoint.update(constrained_yaw_rate, dt); + + } else { + _adjusted_yaw_rate_setpoint.setForcedValue(constrained_yaw_rate); } - _adjusted_yaw_rate_setpoint.update(constrained_yaw_rate, dt); + // Feed forward + steering_setpoint = atanf(_adjusted_yaw_rate_setpoint.getState() * _param_ra_wheel_base.get() / _estimated_speed); + + // Feedback (Only when driving forwards because backwards driving is NMP and can introduce instability) + if (_estimated_speed > FLT_EPSILON) { + _pid_yaw_rate.setSetpoint(_adjusted_yaw_rate_setpoint.getState()); + steering_setpoint += _pid_yaw_rate.update(_vehicle_yaw_rate, dt); + } + + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = _timestamp; + rover_steering_setpoint.normalized_steering_angle = math::interpolate(steering_setpoint, + -_param_ra_max_str_ang.get(), _param_ra_max_str_ang.get(), -1.f, 1.f); // Normalize steering setpoint + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); } else { - _adjusted_yaw_rate_setpoint.setForcedValue(constrained_yaw_rate); + _pid_yaw_rate.resetIntegral(); + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = _timestamp; + rover_steering_setpoint.normalized_steering_angle = 0.f; + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); } - - // Feed forward - steering_setpoint = atanf(_adjusted_yaw_rate_setpoint.getState() * _param_ra_wheel_base.get() / _estimated_speed); - - // Feedback (Only when driving forwards because backwards driving is NMP and can introduce instability) - if (_estimated_speed > FLT_EPSILON) { - _pid_yaw_rate.setSetpoint(_adjusted_yaw_rate_setpoint.getState()); - steering_setpoint += _pid_yaw_rate.update(_vehicle_yaw_rate, dt); - } - - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = _timestamp; - rover_steering_setpoint.normalized_steering_angle = math::interpolate(steering_setpoint, - -_param_ra_max_str_ang.get(), _param_ra_max_str_ang.get(), -1.f, 1.f); // Normalize steering setpoint - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); - - } else { - _pid_yaw_rate.resetIntegral(); - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = _timestamp; - rover_steering_setpoint.normalized_steering_angle = 0.f; - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); } diff --git a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp index 2804d0b8a6..dffbf87758 100644 --- a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp +++ b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp @@ -87,12 +87,6 @@ void AckermannVelControl::updateVelControl() rover_throttle_setpoint.throttle_body_y = NAN; _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - } else { - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = 0.f; - rover_throttle_setpoint.throttle_body_y = NAN; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); } // Publish position controller status (logging only) diff --git a/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp index f2810f06f4..cdedb950c2 100644 --- a/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp +++ b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.cpp @@ -52,27 +52,6 @@ void ManualMode::updateParams() _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; } -void ManualMode::manualControl(const int nav_state) -{ - switch (nav_state) { - case vehicle_status_s::NAVIGATION_STATE_MANUAL: - manual(); - break; - - case vehicle_status_s::NAVIGATION_STATE_ACRO: - acro(); - break; - - case vehicle_status_s::NAVIGATION_STATE_STAB: - stab(); - break; - - case vehicle_status_s::NAVIGATION_STATE_POSCTL: - position(); - break; - } -} - void ManualMode::manual() { manual_control_setpoint_s manual_control_setpoint{}; @@ -121,20 +100,24 @@ void ManualMode::stab() rover_throttle_setpoint.throttle_body_y = 0.f; _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), - _max_yaw_rate / _param_ro_yaw_p.get()); - - if (fabsf(yaw_delta) > FLT_EPSILON - || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { // Closed loop yaw rate control + if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON + || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { _stab_yaw_setpoint = NAN; - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + matrix::sign(manual_control_setpoint.throttle) * yaw_delta); + + // Rate control + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate);; + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); + + // Set uncontrolled setpoint invalid rover_attitude_setpoint_s rover_attitude_setpoint{}; rover_attitude_setpoint.timestamp = hrt_absolute_time(); - rover_attitude_setpoint.yaw_setpoint = yaw_setpoint; + rover_attitude_setpoint.yaw_setpoint = NAN; _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw) + } else { // Heading control if (!PX4_ISFINITE(_stab_yaw_setpoint)) { _stab_yaw_setpoint = _vehicle_yaw; } @@ -173,30 +156,44 @@ void ManualMode::position() const float speed_setpoint = math::interpolate(manual_control_setpoint.throttle, -1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); - const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), - _max_yaw_rate / _param_ro_yaw_p.get()); - if (fabsf(yaw_delta) > FLT_EPSILON - || fabsf(speed_setpoint) < FLT_EPSILON) { // Closed loop yaw rate control + if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON + || fabsf(speed_setpoint) < FLT_EPSILON) { _pos_ctl_course_direction = Vector2f(NAN, NAN); - // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + sign(speed_setpoint) * yaw_delta); - const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); - const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * - pos_ctl_course_direction; + + // Speed control + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = hrt_absolute_time(); + rover_velocity_setpoint.speed = speed_setpoint; + rover_velocity_setpoint.bearing = NAN; + rover_velocity_setpoint.yaw = NAN; + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + // Rate control + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate);; + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); + + // Set uncontrolled setpoints invalid + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = NAN; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + rover_position_setpoint_s rover_position_setpoint{}; rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); - rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.position_ned[0] = NAN; + rover_position_setpoint.position_ned[1] = NAN; rover_position_setpoint.start_ned[0] = NAN; rover_position_setpoint.start_ned[1] = NAN; rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.cruising_speed = NAN; rover_position_setpoint.yaw = NAN; _rover_position_setpoint_pub.publish(rover_position_setpoint); - } else { // Course control if the steering input is zero (keep driving on a straight line) + } else { // Course control if (!_pos_ctl_course_direction.isAllFinite()) { _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); _pos_ctl_start_position_ned = _curr_pos_ned; diff --git a/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp index 8079b326ac..4f6c4a0506 100644 --- a/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp +++ b/src/modules/rover_ackermann/DriveModes/ManualMode/ManualMode.hpp @@ -67,23 +67,6 @@ public: ManualMode(ModuleParams *parent); ~ManualMode() = default; - /** - * @brief Generate and publish roverSetpoints from manualControlSetpoints. - */ - void manualControl(int nav_state); - - /** - * @brief Reset manual mode variables. - */ - void reset(); - -protected: - /** - * @brief Update the parameters of the module. - */ - void updateParams() override; - -private: /** * @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint. */ @@ -104,6 +87,18 @@ private: */ void position(); + /** + * @brief Reset manual mode variables. + */ + void reset(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: // uORB subscriptions uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index 236ecb6af2..f22676e3fa 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -66,13 +66,18 @@ void RoverAckermann::Run() vehicle_control_mode_s vehicle_control_mode{}; _vehicle_control_mode_sub.copy(&vehicle_control_mode); - // Run sanity checks if the control mode changes (Note: This has to be done this way, because the topic is periodically updated and not on changes) - if (vehicle_control_mode.flag_control_position_enabled != _vehicle_control_mode.flag_control_position_enabled || - vehicle_control_mode.flag_control_velocity_enabled != _vehicle_control_mode.flag_control_velocity_enabled || - vehicle_control_mode.flag_control_attitude_enabled != _vehicle_control_mode.flag_control_attitude_enabled || - vehicle_control_mode.flag_control_rates_enabled != _vehicle_control_mode.flag_control_rates_enabled) { + // Run sanity checks if the control mode changes (Note: This has to be done this way, because the topic is periodically updated at 2 Hz) + if (_vehicle_control_mode.flag_control_manual_enabled != vehicle_control_mode.flag_control_manual_enabled || + _vehicle_control_mode.flag_control_auto_enabled != vehicle_control_mode.flag_control_auto_enabled || + _vehicle_control_mode.flag_control_offboard_enabled != vehicle_control_mode.flag_control_offboard_enabled || + _vehicle_control_mode.flag_control_position_enabled != vehicle_control_mode.flag_control_position_enabled || + _vehicle_control_mode.flag_control_velocity_enabled != vehicle_control_mode.flag_control_velocity_enabled || + _vehicle_control_mode.flag_control_attitude_enabled != vehicle_control_mode.flag_control_attitude_enabled || + _vehicle_control_mode.flag_control_rates_enabled != vehicle_control_mode.flag_control_rates_enabled || + _vehicle_control_mode.flag_control_allocation_enabled != vehicle_control_mode.flag_control_allocation_enabled) { _vehicle_control_mode = vehicle_control_mode; runSanityChecks(); + reset(); } else { _vehicle_control_mode = vehicle_control_mode; @@ -80,20 +85,13 @@ void RoverAckermann::Run() } - if (_vehicle_status_sub.updated()) { - vehicle_status_s vehicle_status{}; - _vehicle_status_sub.copy(&vehicle_status); - - // Reset all controllers if the navigation state changes - if (vehicle_status.nav_state != _nav_state) { reset();} - - _nav_state = vehicle_status.nav_state; - } - if (_vehicle_control_mode.flag_armed && _sanity_checks_passed) { + + _was_armed = true; + // Generate setpoints if (_vehicle_control_mode.flag_control_manual_enabled) { - _manual_mode.manualControl(_nav_state); + manualControl(); } else if (_vehicle_control_mode.flag_control_auto_enabled) { _auto_mode.autoControl(); @@ -112,6 +110,22 @@ void RoverAckermann::Run() } +void RoverAckermann::manualControl() +{ + if (_vehicle_control_mode.flag_control_position_enabled) { + _manual_mode.position(); + + } else if (_vehicle_control_mode.flag_control_attitude_enabled) { + _manual_mode.stab(); + + } else if (_vehicle_control_mode.flag_control_rates_enabled) { + _manual_mode.acro(); + + } else if (_vehicle_control_mode.flag_control_allocation_enabled) { + _manual_mode.manual(); + } +} + void RoverAckermann::updateControllers() { if (_vehicle_control_mode.flag_control_position_enabled) { diff --git a/src/modules/rover_ackermann/RoverAckermann.hpp b/src/modules/rover_ackermann/RoverAckermann.hpp index c9f8370afa..a0232b4b45 100644 --- a/src/modules/rover_ackermann/RoverAckermann.hpp +++ b/src/modules/rover_ackermann/RoverAckermann.hpp @@ -48,7 +48,6 @@ #include #include #include -#include // Local includes #include "AckermannActControl/AckermannActControl.hpp" @@ -90,6 +89,11 @@ protected: private: void Run() override; + /** + * @brief Generate and publish roverSetpoints from manualControlSetpoints. + */ + void manualControl(); + /** * @brief Update the active controllers. */ @@ -112,7 +116,6 @@ private: // uORB subscriptions uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; vehicle_control_mode_s _vehicle_control_mode{}; // Class instances @@ -126,7 +129,6 @@ private: OffboardMode _offboard_mode{this}; // Variables - int _nav_state{0}; // Navigation state of the vehicle bool _sanity_checks_passed{true}; // True if checks for all active controllers pass bool _was_armed{false}; // True if the vehicle was armed before the last reset }; From 7c77cfa6e1ab2d30caa4b0f47aa43cdb32601243 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 19 May 2025 10:13:22 +1200 Subject: [PATCH 049/130] holybro: match AP flash layout That way the ArduPilot bootloader works with PX4. --- boards/holybro/kakuteh7-wing/default.px4board | 5 +---- boards/holybro/kakuteh7-wing/firmware.prototype | 2 +- boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld | 2 +- boards/holybro/kakuteh7-wing/src/init.c | 1 + 4 files changed, 4 insertions(+), 6 deletions(-) diff --git a/boards/holybro/kakuteh7-wing/default.px4board b/boards/holybro/kakuteh7-wing/default.px4board index 08670e4781..97e9d53b52 100644 --- a/boards/holybro/kakuteh7-wing/default.px4board +++ b/boards/holybro/kakuteh7-wing/default.px4board @@ -13,13 +13,11 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y -CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_OSD_ATXXXX=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y -CONFIG_COMMON_OPTICAL_FLOW=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_COMMON_TELEMETRY=y @@ -58,9 +56,7 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y -CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_BSONDUMP=y CONFIG_SYSTEMCMDS_DMESG=y @@ -70,6 +66,7 @@ CONFIG_SYSTEMCMDS_MFT=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y diff --git a/boards/holybro/kakuteh7-wing/firmware.prototype b/boards/holybro/kakuteh7-wing/firmware.prototype index 5c3a914540..109266ad37 100644 --- a/boards/holybro/kakuteh7-wing/firmware.prototype +++ b/boards/holybro/kakuteh7-wing/firmware.prototype @@ -7,7 +7,7 @@ "summary": "KAKUTEH7-WING", "version": "0.1", "image_size": 0, - "image_maxsize": 1835008, + "image_maxsize": 1703936, "git_identity": "", "board_revision": 0 } diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld b/boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld index ae07f4bfca..31780fad15 100644 --- a/boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld +++ b/boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld @@ -110,7 +110,7 @@ MEMORY { ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K - FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */ + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1664K /* params in last two sectors */ DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K diff --git a/boards/holybro/kakuteh7-wing/src/init.c b/boards/holybro/kakuteh7-wing/src/init.c index 0e3d27db7d..5908f71f2f 100644 --- a/boards/holybro/kakuteh7-wing/src/init.c +++ b/boards/holybro/kakuteh7-wing/src/init.c @@ -254,6 +254,7 @@ __EXPORT int board_app_initialize(uintptr_t arg) #if defined(FLASH_BASED_PARAMS) static sector_descriptor_t params_sector_map[] = { + {14, 128 * 1024, 0x081C0000}, {15, 128 * 1024, 0x081E0000}, {0, 0, 0}, }; From 9595f123274344c3835306688d0b3b44f17e1efd Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 19 May 2025 12:50:05 +1200 Subject: [PATCH 050/130] holybro: fixup Wing system power setup I don't think we have a way to explicitly detect if BAT1 or BAT2 "bricks" are correct, so we have to assume they are, and rely on the voltage/current shown. Additionally, we can now power cycle sensor power. --- .../holybro/kakuteh7-wing/src/board_config.h | 23 ++++++++----------- boards/holybro/kakuteh7-wing/src/init.c | 16 ++++--------- 2 files changed, 15 insertions(+), 24 deletions(-) diff --git a/boards/holybro/kakuteh7-wing/src/board_config.h b/boards/holybro/kakuteh7-wing/src/board_config.h index 3e70a227f4..b6ba3321e9 100644 --- a/boards/holybro/kakuteh7-wing/src/board_config.h +++ b/boards/holybro/kakuteh7-wing/src/board_config.h @@ -114,7 +114,6 @@ #define BOARD_NUMBER_BRICKS 2 -// TODO: fix #define GPIO_nVDD_BRICK1_VALID (1) /* Brick 1 Is Chosen */ #define GPIO_nVDD_BRICK2_VALID (0) /* Brick 2 Is Chosen */ @@ -129,17 +128,15 @@ */ #define UAVCAN_NUM_IFACES_RUNTIME 1 -#define GPIO_VDD_5V_PERIPH_nEN /* PE2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) -#define GPIO_VDD_5V_PERIPH_nOC /* PE3 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN3) -#define GPIO_VDD_5V_HIPOWER_nEN /* PC10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN10) -#define GPIO_VDD_5V_HIPOWER_nOC /* PC11 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTC|GPIO_PIN11) -#define GPIO_VDD_3V3_SENSORS_EN /* PB2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN2) +#define GPIO_VDD_3V3_SENSORS_EN /* PB2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN2) + +#define GPIO_VTX_9V_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) /* Define True logic Power Control in arch agnostic form */ -#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) -#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) -#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) +#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true)) + +#define VTX_9V_EN(on_true) px4_arch_gpiowrite(GPIO_VTX_9V_EN, (on_true)) /* Tone alarm output */ @@ -196,11 +193,10 @@ #define BOARD_ADC_SERVO_VALID (1) -#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) -#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#define BOARD_ADC_BRICK1_VALID (1) +#define BOARD_ADC_BRICK2_VALID (1) -#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) -#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) +#define BOARD_ADC_SERVO_VALID (1) /* This board provides a DMA pool and APIs */ @@ -217,6 +213,7 @@ GPIO_VDD_3V3_SENSORS_EN, \ GPIO_TONE_ALARM_IDLE, \ GPIO_PPM_IN, \ + GPIO_VTX_9V_EN, \ } #define BOARD_ENABLE_CONSOLE_BUFFER diff --git a/boards/holybro/kakuteh7-wing/src/init.c b/boards/holybro/kakuteh7-wing/src/init.c index 5908f71f2f..4d93e5c16a 100644 --- a/boards/holybro/kakuteh7-wing/src/init.c +++ b/boards/holybro/kakuteh7-wing/src/init.c @@ -108,21 +108,19 @@ __END_DECLS ************************************************************************************/ __EXPORT void board_peripheral_reset(int ms) { - /* set the peripheral rails off */ + /* off */ + VTX_9V_EN(false); + VDD_3V3_SENSORS_EN(false); - VDD_5V_PERIPH_EN(false); board_control_spi_sensors_power(false, 0xffff); - /* wait for the peripheral rail to reach GND */ usleep(ms * 1000); syslog(LOG_DEBUG, "reset done, %d ms\n", ms); /* re-enable power */ - - /* switch the peripheral rail back on */ board_control_spi_sensors_power(true, 0xffff); - VDD_5V_PERIPH_EN(true); - + VDD_3V3_SENSORS_EN(true); + VTX_9V_EN(true); } /************************************************************************************ @@ -210,10 +208,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) { #if !defined(BOOTLOADER) - /* Power on Interfaces */ - VDD_5V_PERIPH_EN(true); - VDD_5V_HIPOWER_EN(true); - /* Need hrt running before using the ADC */ px4_platform_init(); From c9145a24b46cf0f8db19331af9f04ccd2f558948 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 20 May 2025 11:59:33 +1200 Subject: [PATCH 051/130] holybro: hard-select CAM1 for now I don't think there is an easy way to hook this up to RC input at the moment, so I'm setting it fixed to CAM1 for now. --- boards/holybro/kakuteh7-wing/src/board_config.h | 6 ++++++ boards/holybro/kakuteh7-wing/src/init.c | 2 ++ 2 files changed, 8 insertions(+) diff --git a/boards/holybro/kakuteh7-wing/src/board_config.h b/boards/holybro/kakuteh7-wing/src/board_config.h index b6ba3321e9..2583282495 100644 --- a/boards/holybro/kakuteh7-wing/src/board_config.h +++ b/boards/holybro/kakuteh7-wing/src/board_config.h @@ -132,12 +132,17 @@ #define GPIO_VTX_9V_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +#define GPIO_CAM_SWITCH /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + /* Define True logic Power Control in arch agnostic form */ #define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true)) #define VTX_9V_EN(on_true) px4_arch_gpiowrite(GPIO_VTX_9V_EN, (on_true)) +#define CAM_SWITCH_CAM1 px4_arch_gpiowrite(GPIO_CAM_SWITCH, false) // low is CAM1 +#define CAM_SWITCH_CAM2 px4_arch_gpiowrite(GPIO_CAM_SWITCH, true) // high is CAM2 + /* Tone alarm output */ #define TONE_ALARM_TIMER 17 /* Timer 17 */ @@ -214,6 +219,7 @@ GPIO_TONE_ALARM_IDLE, \ GPIO_PPM_IN, \ GPIO_VTX_9V_EN, \ + GPIO_CAM_SWITCH, \ } #define BOARD_ENABLE_CONSOLE_BUFFER diff --git a/boards/holybro/kakuteh7-wing/src/init.c b/boards/holybro/kakuteh7-wing/src/init.c index 4d93e5c16a..5fbe50c6a6 100644 --- a/boards/holybro/kakuteh7-wing/src/init.c +++ b/boards/holybro/kakuteh7-wing/src/init.c @@ -121,6 +121,8 @@ __EXPORT void board_peripheral_reset(int ms) board_control_spi_sensors_power(true, 0xffff); VDD_3V3_SENSORS_EN(true); VTX_9V_EN(true); + + CAM_SWITCH_CAM1; } /************************************************************************************ From 3bbe3e5268e74c50c047559ca092bc99e5a06220 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Thu, 22 May 2025 17:42:09 -0800 Subject: [PATCH 052/130] logger: add new mask for high rate sensors --- src/modules/logger/logged_topics.cpp | 12 ++++++++++++ src/modules/logger/logged_topics.h | 4 +++- src/modules/logger/params.c | 3 ++- 3 files changed, 17 insertions(+), 2 deletions(-) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 3d011cbc5c..faaf26dace 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -363,6 +363,14 @@ void LoggedTopics::add_system_identification_topics() add_topic("actuator_motors"); } +void LoggedTopics::add_high_rate_sensors_topics() +{ + add_topic_multi("distance_sensor", 0, 4); + add_topic_multi("sensor_optical_flow", 0, 2); + add_topic_multi("sensor_gps", 0, 4); + add_topic_multi("sensor_mag", 0, 4); +} + void LoggedTopics::add_mavlink_tunnel() { add_topic("mavlink_tunnel"); @@ -578,4 +586,8 @@ void LoggedTopics::initialize_configured_topics(SDLogProfileMask profile) if (profile & SDLogProfileMask::MAVLINK_TUNNEL) { add_mavlink_tunnel(); } + + if (profile & SDLogProfileMask::HIGH_RATE_SENSORS) { + add_high_rate_sensors_topics(); + } } diff --git a/src/modules/logger/logged_topics.h b/src/modules/logger/logged_topics.h index de27574ce8..e7eb7676b6 100644 --- a/src/modules/logger/logged_topics.h +++ b/src/modules/logger/logged_topics.h @@ -54,7 +54,8 @@ enum class SDLogProfileMask : int32_t { VISION_AND_AVOIDANCE = 1 << 7, RAW_IMU_GYRO_FIFO = 1 << 8, RAW_IMU_ACCEL_FIFO = 1 << 9, - MAVLINK_TUNNEL = 1 << 10 + MAVLINK_TUNNEL = 1 << 10, + HIGH_RATE_SENSORS = 1 << 11 }; enum class MissionLogType : int32_t { @@ -175,6 +176,7 @@ private: void add_raw_imu_gyro_fifo(); void add_raw_imu_accel_fifo(); void add_mavlink_tunnel(); + void add_high_rate_sensors_topics(); /** * add a logged topic (called by add_topic() above). diff --git a/src/modules/logger/params.c b/src/modules/logger/params.c index e1bbd5145f..cb734ac1af 100644 --- a/src/modules/logger/params.c +++ b/src/modules/logger/params.c @@ -129,7 +129,7 @@ PARAM_DEFINE_INT32(SDLOG_MISSION, 0); * 10: Logging of mavlink tunnel message (useful for payload communication debugging) * * @min 0 - * @max 2047 + * @max 4095 * @bit 0 Default set (general log analysis) * @bit 1 Estimator replay (EKF2) * @bit 2 Thermal calibration @@ -141,6 +141,7 @@ PARAM_DEFINE_INT32(SDLOG_MISSION, 0); * @bit 8 Raw FIFO high-rate IMU (Gyro) * @bit 9 Raw FIFO high-rate IMU (Accel) * @bit 10 Mavlink tunnel message logging + * @bit 11 High rate sensors * @reboot_required true * @group SD Logging */ From 8c6d7235e44a7a00375b63eb1893b8e1cb789c6f Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Tue, 27 May 2025 10:24:05 +0200 Subject: [PATCH 053/130] [drivers] Allow swapping RX/TX pins of DShot Telemetry --- .../auterion/fmu-v6s/init/rc.board_defaults | 3 ++ boards/hkust/nxt-dual/init/rc.board_extras | 2 +- boards/hkust/nxt-v1/init/rc.board_extras | 2 +- boards/holybro/kakutef7/init/rc.board_extras | 2 +- boards/holybro/kakuteh7/init/rc.board_extras | 2 +- .../kakuteh7dualimu/init/rc.board_extras | 2 +- .../holybro/kakuteh7mini/init/rc.board_extras | 2 +- .../holybro/kakuteh7v2/init/rc.board_extras | 2 +- boards/matek/h743-mini/init/rc.board_extras | 2 +- boards/matek/h743-slim/init/rc.board_extras | 2 +- boards/matek/h743/init/rc.board_extras | 2 +- boards/x-mav/ap-h743v2/init/rc.board_extras | 2 +- src/drivers/dshot/DShot.cpp | 45 ++++++++++++------- src/drivers/dshot/DShot.h | 3 +- src/drivers/dshot/DShotTelemetry.cpp | 15 ++++++- src/drivers/dshot/DShotTelemetry.h | 2 +- src/drivers/dshot/module.yaml | 2 +- 17 files changed, 61 insertions(+), 31 deletions(-) diff --git a/boards/auterion/fmu-v6s/init/rc.board_defaults b/boards/auterion/fmu-v6s/init/rc.board_defaults index b68b2b1b98..0a568ec30a 100644 --- a/boards/auterion/fmu-v6s/init/rc.board_defaults +++ b/boards/auterion/fmu-v6s/init/rc.board_defaults @@ -26,3 +26,6 @@ nshterm /dev/ttyS3 & # Start the time_persistor to cyclically store the RTC in FRAM time_persistor start + +# Start the ESC telemetry +dshot telemetry -d /dev/ttyS5 -x diff --git a/boards/hkust/nxt-dual/init/rc.board_extras b/boards/hkust/nxt-dual/init/rc.board_extras index 780b13dc96..4611dbae46 100644 --- a/boards/hkust/nxt-dual/init/rc.board_extras +++ b/boards/hkust/nxt-dual/init/rc.board_extras @@ -10,4 +10,4 @@ # fi # DShot telemetry is always on UART7 -# dshot telemetry /dev/ttyS5 +# dshot telemetry -d /dev/ttyS5 diff --git a/boards/hkust/nxt-v1/init/rc.board_extras b/boards/hkust/nxt-v1/init/rc.board_extras index 780b13dc96..4611dbae46 100644 --- a/boards/hkust/nxt-v1/init/rc.board_extras +++ b/boards/hkust/nxt-v1/init/rc.board_extras @@ -10,4 +10,4 @@ # fi # DShot telemetry is always on UART7 -# dshot telemetry /dev/ttyS5 +# dshot telemetry -d /dev/ttyS5 diff --git a/boards/holybro/kakutef7/init/rc.board_extras b/boards/holybro/kakutef7/init/rc.board_extras index 5822cd2945..33af1f8226 100644 --- a/boards/holybro/kakutef7/init/rc.board_extras +++ b/boards/holybro/kakutef7/init/rc.board_extras @@ -9,4 +9,4 @@ then fi # DShot telemetry is always on UART7 -dshot telemetry /dev/ttyS5 +dshot telemetry -d /dev/ttyS5 diff --git a/boards/holybro/kakuteh7/init/rc.board_extras b/boards/holybro/kakuteh7/init/rc.board_extras index 3423728dab..3629cd2958 100644 --- a/boards/holybro/kakuteh7/init/rc.board_extras +++ b/boards/holybro/kakuteh7/init/rc.board_extras @@ -9,4 +9,4 @@ then fi # DShot telemetry is always on UART7 -dshot telemetry /dev/ttyS5 +dshot telemetry -d /dev/ttyS5 diff --git a/boards/holybro/kakuteh7dualimu/init/rc.board_extras b/boards/holybro/kakuteh7dualimu/init/rc.board_extras index 3423728dab..3629cd2958 100644 --- a/boards/holybro/kakuteh7dualimu/init/rc.board_extras +++ b/boards/holybro/kakuteh7dualimu/init/rc.board_extras @@ -9,4 +9,4 @@ then fi # DShot telemetry is always on UART7 -dshot telemetry /dev/ttyS5 +dshot telemetry -d /dev/ttyS5 diff --git a/boards/holybro/kakuteh7mini/init/rc.board_extras b/boards/holybro/kakuteh7mini/init/rc.board_extras index 3423728dab..3629cd2958 100644 --- a/boards/holybro/kakuteh7mini/init/rc.board_extras +++ b/boards/holybro/kakuteh7mini/init/rc.board_extras @@ -9,4 +9,4 @@ then fi # DShot telemetry is always on UART7 -dshot telemetry /dev/ttyS5 +dshot telemetry -d /dev/ttyS5 diff --git a/boards/holybro/kakuteh7v2/init/rc.board_extras b/boards/holybro/kakuteh7v2/init/rc.board_extras index 3423728dab..3629cd2958 100644 --- a/boards/holybro/kakuteh7v2/init/rc.board_extras +++ b/boards/holybro/kakuteh7v2/init/rc.board_extras @@ -9,4 +9,4 @@ then fi # DShot telemetry is always on UART7 -dshot telemetry /dev/ttyS5 +dshot telemetry -d /dev/ttyS5 diff --git a/boards/matek/h743-mini/init/rc.board_extras b/boards/matek/h743-mini/init/rc.board_extras index 66e2936464..68ccc31a1d 100644 --- a/boards/matek/h743-mini/init/rc.board_extras +++ b/boards/matek/h743-mini/init/rc.board_extras @@ -11,4 +11,4 @@ atxxxx start -s # DShot telemetry is always on UART7 -# dshot telemetry /dev/ttyS5 +# dshot telemetry -d /dev/ttyS5 diff --git a/boards/matek/h743-slim/init/rc.board_extras b/boards/matek/h743-slim/init/rc.board_extras index bba363769c..61c6c0afb0 100644 --- a/boards/matek/h743-slim/init/rc.board_extras +++ b/boards/matek/h743-slim/init/rc.board_extras @@ -12,4 +12,4 @@ atxxxx start -s # DShot telemetry is always on UART7 -# dshot telemetry /dev/ttyS5 +# dshot telemetry -d /dev/ttyS5 diff --git a/boards/matek/h743/init/rc.board_extras b/boards/matek/h743/init/rc.board_extras index bba363769c..61c6c0afb0 100644 --- a/boards/matek/h743/init/rc.board_extras +++ b/boards/matek/h743/init/rc.board_extras @@ -12,4 +12,4 @@ atxxxx start -s # DShot telemetry is always on UART7 -# dshot telemetry /dev/ttyS5 +# dshot telemetry -d /dev/ttyS5 diff --git a/boards/x-mav/ap-h743v2/init/rc.board_extras b/boards/x-mav/ap-h743v2/init/rc.board_extras index 780b13dc96..4611dbae46 100644 --- a/boards/x-mav/ap-h743v2/init/rc.board_extras +++ b/boards/x-mav/ap-h743v2/init/rc.board_extras @@ -10,4 +10,4 @@ # fi # DShot telemetry is always on UART7 -# dshot telemetry /dev/ttyS5 +# dshot telemetry -d /dev/ttyS5 diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 10c356ade1..db6e16bf7d 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -38,6 +38,7 @@ #include char DShot::_telemetry_device[] {}; +bool DShot::_telemetry_swap_rxtx{false}; px4::atomic_bool DShot::_request_telemetry_init{false}; DShot::DShot() : @@ -189,7 +190,7 @@ void DShot::update_num_motors() _num_motors = motor_count; } -void DShot::init_telemetry(const char *device) +void DShot::init_telemetry(const char *device, bool swap_rxtx) { if (!_telemetry) { _telemetry = new DShotTelemetry{}; @@ -201,7 +202,7 @@ void DShot::init_telemetry(const char *device) } if (device != NULL) { - int ret = _telemetry->init(device); + int ret = _telemetry->init(device, swap_rxtx); if (ret != 0) { PX4_ERR("telemetry init failed (%i)", ret); @@ -574,7 +575,7 @@ void DShot::Run() // telemetry device update request? if (_request_telemetry_init.load()) { - init_telemetry(_telemetry_device); + init_telemetry(_telemetry_device, _telemetry_swap_rxtx); _request_telemetry_init.store(false); } @@ -703,33 +704,44 @@ int DShot::custom_command(int argc, char *argv[]) { const char *verb = argv[0]; - if (!strcmp(verb, "telemetry")) { - if (argc > 1) { - // telemetry can be requested before the module is started - strncpy(_telemetry_device, argv[1], sizeof(_telemetry_device) - 1); - _telemetry_device[sizeof(_telemetry_device) - 1] = '\0'; - _request_telemetry_init.store(true); - } - - return 0; - } - int motor_index = -1; // select motor index, default: -1=all int myoptind = 1; + bool swap_rxtx = false; + const char *device_name = nullptr; int ch; const char *myoptarg = nullptr; - while ((ch = px4_getopt(argc, argv, "m:", &myoptind, &myoptarg)) != EOF) { + while ((ch = px4_getopt(argc, argv, "m:xd:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'm': motor_index = strtol(myoptarg, nullptr, 10) - 1; break; + case 'x': + swap_rxtx = true; + break; + + case 'd': + device_name = myoptarg; + break; + default: return print_usage("unrecognized flag"); } } + if (!strcmp(verb, "telemetry")) { + if (device_name) { + // telemetry can be requested before the module is started + strncpy(_telemetry_device, device_name, sizeof(_telemetry_device) - 1); + _telemetry_device[sizeof(_telemetry_device) - 1] = '\0'; + _telemetry_swap_rxtx = swap_rxtx; + _request_telemetry_init.store(true); + } + + return 0; + } + struct VerbCommand { const char *name; dshot_command_t command; @@ -844,7 +856,8 @@ After saving, the reversed direction will be regarded as the normal one. So to r PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_COMMAND_DESCR("telemetry", "Enable Telemetry on a UART"); - PRINT_MODULE_USAGE_ARG("", "UART device", false); + PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "UART device", false); + PRINT_MODULE_USAGE_PARAM_FLAG('x', "Swap RX/TX pins", true); // DShot commands PRINT_MODULE_USAGE_COMMAND_DESCR("reverse", "Reverse motor direction"); diff --git a/src/drivers/dshot/DShot.h b/src/drivers/dshot/DShot.h index 9b4d8cfb48..d0300d0470 100644 --- a/src/drivers/dshot/DShot.h +++ b/src/drivers/dshot/DShot.h @@ -123,7 +123,7 @@ private: void enable_dshot_outputs(const bool enabled); - void init_telemetry(const char *device); + void init_telemetry(const char *device, bool swap_rxtx); int handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data, bool ignore_rpm); @@ -149,6 +149,7 @@ private: uORB::PublicationMultiData esc_status_pub{ORB_ID(esc_status)}; static char _telemetry_device[20]; + static bool _telemetry_swap_rxtx; static px4::atomic_bool _request_telemetry_init; px4::atomic _new_command{nullptr}; diff --git a/src/drivers/dshot/DShotTelemetry.cpp b/src/drivers/dshot/DShotTelemetry.cpp index 70992b1703..fe75b36854 100644 --- a/src/drivers/dshot/DShotTelemetry.cpp +++ b/src/drivers/dshot/DShotTelemetry.cpp @@ -49,7 +49,7 @@ DShotTelemetry::~DShotTelemetry() deinit(); } -int DShotTelemetry::init(const char *uart_device) +int DShotTelemetry::init(const char *uart_device, bool swap_rxtx) { deinit(); _uart_fd = ::open(uart_device, O_RDONLY | O_NOCTTY); @@ -59,6 +59,19 @@ int DShotTelemetry::init(const char *uart_device) return -errno; } + if (swap_rxtx) { + // Swap RX/TX pins if the device supports it + int rv = ioctl(_uart_fd, TIOCSSWAP, SER_SWAP_ENABLED); + + // For other devices we can still place RX on TX pin via half-duplex single-wire mode + if (rv) { rv = ioctl(_uart_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); } + + if (rv) { + PX4_ERR("failed to swap rx/tx pins: %s err: %d", uart_device, rv); + return rv; + } + } + _num_timeouts = 0; _num_successful_responses = 0; _current_motor_index_request = -1; diff --git a/src/drivers/dshot/DShotTelemetry.h b/src/drivers/dshot/DShotTelemetry.h index 8672e85f7f..1c5c14ef25 100644 --- a/src/drivers/dshot/DShotTelemetry.h +++ b/src/drivers/dshot/DShotTelemetry.h @@ -60,7 +60,7 @@ public: ~DShotTelemetry(); - int init(const char *uart_device); + int init(const char *uart_device, bool swap_rxtx); void deinit(); diff --git a/src/drivers/dshot/module.yaml b/src/drivers/dshot/module.yaml index e2dcf8bc97..a31d394815 100644 --- a/src/drivers/dshot/module.yaml +++ b/src/drivers/dshot/module.yaml @@ -1,6 +1,6 @@ module_name: DShot Driver serial_config: - - command: dshot telemetry ${SERIAL_DEV} + - command: dshot telemetry -d ${SERIAL_DEV} port_config_param: name: DSHOT_TEL_CFG group: DShot From 238dffcd1b71e5ceb2f30ac817706d20da03c0d0 Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Fri, 23 May 2025 12:38:28 +0200 Subject: [PATCH 054/130] uxrce_client: add option to set polling rate limit per topic --- src/modules/uxrce_dds_client/dds_topics.h.em | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/uxrce_dds_client/dds_topics.h.em b/src/modules/uxrce_dds_client/dds_topics.h.em index deba362668..7ff7605ccd 100644 --- a/src/modules/uxrce_dds_client/dds_topics.h.em +++ b/src/modules/uxrce_dds_client/dds_topics.h.em @@ -30,7 +30,7 @@ import os #include @[end for]@ -#define UXRCE_DEFAULT_POLL_RATE 10 +#define UXRCE_DEFAULT_POLL_INTERVAL_MS 10 typedef bool (*UcdrSerializeMethod)(const void* data, ucdrBuffer& buf, int64_t time_offset); @@ -66,6 +66,7 @@ struct SendSubscription { uint32_t message_version; uint32_t topic_size; UcdrSerializeMethod ucdr_serialize_method; + uint64_t publish_interval_ms; }; // Subscribers for messages to send @@ -79,6 +80,7 @@ struct SendTopicsSubs { get_message_version<@(pub['simple_base_type'])_s>(), ucdr_topic_size_@(pub['simple_base_type'])(), &ucdr_serialize_@(pub['simple_base_type']), + static_cast((@(pub.get('rate_limit', 0)) > 0) ? (1e3 / @(pub.get('rate_limit', 1e3))) : UXRCE_DEFAULT_POLL_INTERVAL_MS), }, @[ end for]@ }; @@ -98,7 +100,7 @@ bool SendTopicsSubs::init(uxrSession *session, uxrStreamId reliable_out_stream_i if (fds[idx].events == 0) { fds[idx].fd = orb_subscribe(send_subscriptions[idx].orb_meta); fds[idx].events = POLLIN; - orb_set_interval(fds[idx].fd, UXRCE_DEFAULT_POLL_RATE); + orb_set_interval(fds[idx].fd, send_subscriptions[idx].publish_interval_ms); } if (!create_data_writer(session, reliable_out_stream_id, participant_id, static_cast(send_subscriptions[idx].orb_meta->o_id), client_namespace, send_subscriptions[idx].topic, From b7702d36045aa9a227faed2190edffc0a10c6fb8 Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Fri, 23 May 2025 12:39:00 +0200 Subject: [PATCH 055/130] docs: uxrce_dds rate_limit option --- docs/en/middleware/uxrce_dds.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs/en/middleware/uxrce_dds.md b/docs/en/middleware/uxrce_dds.md index 1872c447d3..c24b67fa1e 100644 --- a/docs/en/middleware/uxrce_dds.md +++ b/docs/en/middleware/uxrce_dds.md @@ -428,9 +428,11 @@ publications: - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry + rate_limit: 150. - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus + rate_limit: 50. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint @@ -465,6 +467,8 @@ Each (`topic`,`type`) pairs defines: - `/fmu/out/` for topics that are _published_ by PX4. - `/fmu/in/` for topics that are _subscribed_ by PX4. 4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition. +5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2. + If left unspecified, the maximum publication rate limit is set to 100 Hz. `subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively. Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers. From e1167f0888ec7a747beff72a7a76459a00ec415a Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Fri, 23 May 2025 12:40:01 +0200 Subject: [PATCH 056/130] dds_topics: rate limit BatteryStatus ROS2 publication to 1 Hz --- src/modules/uxrce_dds_client/dds_topics.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index a1e33be861..86f638a454 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -16,6 +16,7 @@ publications: - topic: /fmu/out/battery_status type: px4_msgs::msg::BatteryStatus + rate_limit: 1. - topic: /fmu/out/collision_constraints type: px4_msgs::msg::CollisionConstraints From 4abe2d1dabc37d94d4a327b004a425f042f6a18b Mon Sep 17 00:00:00 2001 From: Mahima Yoga Date: Fri, 23 May 2025 11:39:53 +0200 Subject: [PATCH 057/130] Navigator: allow executing a disarm command during a mission --- src/modules/mavlink/mavlink_mission.cpp | 6 ++++++ .../navigator/MissionFeasibility/FeasibilityChecker.cpp | 1 + src/modules/navigator/mission_block.cpp | 2 ++ src/modules/navigator/navigation.h | 1 + 4 files changed, 10 insertions(+) diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 36d4453344..c24796b19d 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -1527,6 +1527,11 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command; break; + case MAV_CMD_COMPONENT_ARM_DISARM: + mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command; + mission_item->params[0] = (uint16_t)mavlink_mission_item->param1; + break; + default: mission_item->nav_cmd = NAV_CMD_INVALID; PX4_DEBUG("Unsupported command %d", mavlink_mission_item->command); @@ -1616,6 +1621,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * case MAV_CMD_CONDITION_DELAY: case MAV_CMD_CONDITION_DISTANCE: case MAV_CMD_DO_SET_ACTUATOR: + case MAV_CMD_COMPONENT_ARM_DISARM: mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command; break; diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp index c35d2c1bde..713eb151b7 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp @@ -263,6 +263,7 @@ bool FeasibilityChecker::checkMissionItemValidity(mission_item_s &mission_item, mission_item.nav_cmd != NAV_CMD_DO_LAND_START && mission_item.nav_cmd != NAV_CMD_DO_TRIGGER_CONTROL && mission_item.nav_cmd != NAV_CMD_DO_DIGICAM_CONTROL && + mission_item.nav_cmd != NAV_CMD_COMPONENT_ARM_DISARM && mission_item.nav_cmd != NAV_CMD_IMAGE_START_CAPTURE && mission_item.nav_cmd != NAV_CMD_IMAGE_STOP_CAPTURE && mission_item.nav_cmd != NAV_CMD_VIDEO_START_CAPTURE && diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index 3f2c621baa..3f8bfd3a52 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -82,6 +82,7 @@ MissionBlock::is_mission_item_reached_or_completed() case NAV_CMD_DO_MOUNT_CONFIGURE: case NAV_CMD_DO_MOUNT_CONTROL: case NAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE: + case NAV_CMD_COMPONENT_ARM_DISARM: case NAV_CMD_DO_SET_ROI: case NAV_CMD_DO_SET_ROI_LOCATION: case NAV_CMD_DO_SET_ROI_WPNEXT_OFFSET: @@ -95,6 +96,7 @@ MissionBlock::is_mission_item_reached_or_completed() case NAV_CMD_SET_CAMERA_FOCUS: case NAV_CMD_DO_CHANGE_SPEED: case NAV_CMD_DO_SET_HOME: + return true; // Indefinite Waypoints diff --git a/src/modules/navigator/navigation.h b/src/modules/navigator/navigation.h index 2d31866581..1c32f3042e 100644 --- a/src/modules/navigator/navigation.h +++ b/src/modules/navigator/navigation.h @@ -76,6 +76,7 @@ enum NAV_CMD { NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214, NAV_CMD_DO_SET_CAM_TRIGG_DIST = 206, NAV_CMD_OBLIQUE_SURVEY = 260, + NAV_CMD_COMPONENT_ARM_DISARM = 400, NAV_CMD_SET_CAMERA_MODE = 530, NAV_CMD_SET_CAMERA_SOURCE = 534, NAV_CMD_SET_CAMERA_ZOOM = 531, From ce9bb0dc6bd2501260511b4aa7c20bb233e05d98 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 12 May 2025 10:59:19 +0200 Subject: [PATCH 058/130] multicopter defaults: use PX4 default <2g ublox GNSS dynamic model also for multirotors It currently defaults to 1g for multirotors, which works in most cases. However, during extended high-acceleration flight (e.g. in Stabilized mode), the limited dynamic model can upset the EKF, causing repeated resets due to data inconsistencies. Recovery is sometimes quick but can also be too slow to maintain position after high acceleration flight. This issue was observed on an 850mm vehicle, not a racer. --- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 2 -- 1 file changed, 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index db11cedbb3..995e9ddbab 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -20,7 +20,5 @@ param set-default NAV_ACC_RAD 2 param set-default RTL_RETURN_ALT 30 param set-default RTL_DESCEND_ALT 10 -param set-default GPS_UBX_DYNMODEL 6 - # lower RNG_FOG since MC are expected to fly closer over obstacles param set-default EKF2_RNG_FOG 1.0 From ba11f750679ecd38882f8064efc9f318fd1ee503 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 28 May 2025 10:34:22 +1000 Subject: [PATCH 059/130] CellularStatus.msg - fix to standard (#24928) * CellularStatus.msg - fix to standard * Update CellularStatus.msg --------- Co-authored-by: PX4BuildBot --- msg/CellularStatus.msg | 60 +++++++++++++++++++++--------------------- 1 file changed, 30 insertions(+), 30 deletions(-) diff --git a/msg/CellularStatus.msg b/msg/CellularStatus.msg index 4ced957de4..c2aef7c459 100644 --- a/msg/CellularStatus.msg +++ b/msg/CellularStatus.msg @@ -2,37 +2,37 @@ # # This is currently used only for logging cell status from MAVLink. -uint64 timestamp # Time since system start [us] +uint64 timestamp # [us] Time since system start. -uint16 status # Status bitmap [@enum STATUS_FLAG] -uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable -uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable -uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized -uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked -uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down -uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state -uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state -uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register -uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected +uint16 status # [@enum STATUS_FLAG] Status bitmap. +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable. +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable. +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized. +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked. +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down. +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state. +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state. +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections. +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register. +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use. +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated. +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered. +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected. -uint8 failure_reason # Failure reason [@enum FAILURE_REASON] -uint8 FAILURE_REASON_NONE = 0 # No error -uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown -uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing -uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason. +uint8 FAILURE_REASON_NONE = 0 # No error. +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown. +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing. +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection. -uint8 type # Cellular network radio type [@enum CELLULAR_NETWORK_RADIO_TYPE] -uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 -uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 -uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 -uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 -uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type. +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE -uint8 quality # Cellular network RSSI/RSRP, absolute value [dBm] -uint16 mcc # Mobile country code. [@invalid UINT16_MAX] -uint16 mnc # Mobile network code. [@invalid UINT16_MAX] -uint16 lac # Location area code. [@invalid 0] +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value. +uint16 mcc # [@invalid UINT16_MAX] Mobile country code. +uint16 mnc # [@invalid UINT16_MAX] Mobile network code. +uint16 lac # [@invalid 0] Location area code. From effcb32a3ea67d0bfffeb000274ddd3e4550974b Mon Sep 17 00:00:00 2001 From: Abhishek Choithani Date: Wed, 28 May 2025 07:09:23 +0530 Subject: [PATCH 060/130] Contibuting to docs - open editor on linux (#24907) * Update docs.md Tested on Ubuntu * Fix layout --------- Co-authored-by: Hamish Willee --- docs/en/contribute/docs.md | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/docs/en/contribute/docs.md b/docs/en/contribute/docs.md index 2538e58184..0202b86914 100644 --- a/docs/en/contribute/docs.md +++ b/docs/en/contribute/docs.md @@ -174,11 +174,19 @@ Build the library locally to test that any changes you have made have rendered p 1. Open previewed pages in your local editor: First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. - For example, on Windows command line you can enable VSCode as your default editor by entering: + For example, you can enable VSCode as your default editor by entering: - ```sh - set EDITOR=code - ``` + - Windows: + + ```sh + set EDITOR=code + ``` + + - Linux: + + ```sh + export EDITOR=code + ``` The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). From eb72925045a5866f7ab90cf6fffbc099b0af6aaa Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 28 May 2025 12:23:02 +1000 Subject: [PATCH 061/130] Docs Metadata updates (#24929) * Failsafe metadata update * docs: update module reference metadata * docs: update parameter reference metadata * docs: metadata: update uORB graph JSONs * uorb message metadata updates * Add new uorb topics to sidebar * Remove uorb topics that no longer exist * fix up resulting docs links --------- Co-authored-by: PX4BuildBot --- .../pixhawk6c_mini/pixhawk6c_mini_hero.jpg | Bin 42510 -> 0 bytes .../pixhawk_6x_internal_Architecture.png | Bin 775954 -> 0 bytes .../toolchain/gazebo_classic_takeoff.png | Bin 176472 -> 0 bytes docs/en/SUMMARY.md | 19 +- .../en/advanced_config/parameter_reference.md | 853 +++++++++--------- docs/en/frames_plane/reptile_dragon_2.md | 2 +- docs/en/modules/modules_controller.md | 33 +- docs/en/modules/modules_driver.md | 4 +- docs/en/modules/modules_system.md | 1 + docs/en/msg_docs/AirspeedValidated.md | 26 +- docs/en/msg_docs/AirspeedValidatedV0.md | 27 + docs/en/msg_docs/Buffer128.md | 17 - docs/en/msg_docs/CellularStatus.md | 62 +- .../FixedWingLateralGuidanceStatus.md | 23 + docs/en/msg_docs/FixedWingLateralSetpoint.md | 22 + docs/en/msg_docs/FixedWingLateralStatus.md | 17 + .../msg_docs/FixedWingLongitudinalSetpoint.md | 26 + docs/en/msg_docs/FixedWingRunwayControl.md | 19 + .../msg_docs/LateralControlConfiguration.md | 18 + .../LongitudinalControlConfiguration.md | 28 + docs/en/msg_docs/NpfgStatus.md | 26 - docs/en/msg_docs/PurePursuitStatus.md | 2 - docs/en/msg_docs/RateCtrlStatus.md | 1 - docs/en/msg_docs/RoverAttitudeSetpoint.md | 2 - docs/en/msg_docs/RoverAttitudeStatus.md | 2 - .../en/msg_docs/RoverMecanumGuidanceStatus.md | 16 - docs/en/msg_docs/RoverMecanumSetpoint.md | 20 - docs/en/msg_docs/RoverMecanumStatus.md | 26 - docs/en/msg_docs/RoverPositionSetpoint.md | 17 + docs/en/msg_docs/RoverRateSetpoint.md | 2 - docs/en/msg_docs/RoverRateStatus.md | 2 - docs/en/msg_docs/RoverSteeringSetpoint.md | 5 +- docs/en/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/en/msg_docs/RoverVelocitySetpoint.md | 14 + docs/en/msg_docs/RoverVelocityStatus.md | 10 +- docs/en/msg_docs/TrajectorySetpoint6dof.md | 23 + docs/en/msg_docs/VehicleAttitudeSetpoint.md | 6 +- docs/en/msg_docs/VehicleAttitudeSetpointV0.md | 27 + docs/en/msg_docs/VehicleCommand.md | 256 +++--- docs/en/msg_docs/index.md | 28 +- docs/en/telemetry/crsf_telemetry.md | 2 +- docs/en/tutorials/linux_sbus.md | 10 +- docs/public/config/failsafe/index.js | 2 +- docs/public/config/failsafe/index.wasm | Bin 96332 -> 96229 bytes docs/public/config/failsafe/parameters.json | 2 +- docs/public/middleware/graph_full.json | 2 +- .../middleware/graph_full_no_mavlink.json | 2 +- docs/public/middleware/graph_px4_fmu-v2.json | 2 +- docs/public/middleware/graph_px4_fmu-v4.json | 2 +- docs/public/middleware/graph_px4_fmu-v5.json | 2 +- docs/public/middleware/graph_px4_fmu-v5x.json | 2 +- docs/public/middleware/graph_px4_fmu-v6x.json | 2 +- docs/public/middleware/graph_px4_sitl.json | 2 +- 53 files changed, 937 insertions(+), 783 deletions(-) delete mode 100644 docs/assets/flight_controller/pixhawk6c_mini/pixhawk6c_mini_hero.jpg delete mode 100644 docs/assets/flight_controller/pixhawk6x/pixhawk_6x_internal_Architecture.png delete mode 100644 docs/assets/toolchain/gazebo_classic_takeoff.png create mode 100644 docs/en/msg_docs/AirspeedValidatedV0.md delete mode 100644 docs/en/msg_docs/Buffer128.md create mode 100644 docs/en/msg_docs/FixedWingLateralGuidanceStatus.md create mode 100644 docs/en/msg_docs/FixedWingLateralSetpoint.md create mode 100644 docs/en/msg_docs/FixedWingLateralStatus.md create mode 100644 docs/en/msg_docs/FixedWingLongitudinalSetpoint.md create mode 100644 docs/en/msg_docs/FixedWingRunwayControl.md create mode 100644 docs/en/msg_docs/LateralControlConfiguration.md create mode 100644 docs/en/msg_docs/LongitudinalControlConfiguration.md delete mode 100644 docs/en/msg_docs/NpfgStatus.md delete mode 100644 docs/en/msg_docs/RoverMecanumGuidanceStatus.md delete mode 100644 docs/en/msg_docs/RoverMecanumSetpoint.md delete mode 100644 docs/en/msg_docs/RoverMecanumStatus.md create mode 100644 docs/en/msg_docs/RoverPositionSetpoint.md create mode 100644 docs/en/msg_docs/RoverVelocitySetpoint.md create mode 100644 docs/en/msg_docs/TrajectorySetpoint6dof.md create mode 100644 docs/en/msg_docs/VehicleAttitudeSetpointV0.md diff --git a/docs/assets/flight_controller/pixhawk6c_mini/pixhawk6c_mini_hero.jpg b/docs/assets/flight_controller/pixhawk6c_mini/pixhawk6c_mini_hero.jpg deleted file mode 100644 index cdd3185e691c96a7e57eea948a3723d7fae5f56c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 42510 zcmeFXRajk3vo1PtcP9|s-GaNj+r-@+f&~ddg1fuByC-OHcS~?5xWjqKm$lYD=h^4t zzd7e(fA2-l9yQ*suBxuC(R0r6y7>ANK$Ve@mH@!O000aC1Ay0Gs9oY7R^|X8FAvZH z000X>fT05rz~B2JRsiImJ^(9lNC3b904yQ^0IUE200f7B`2XTx{EL6_FaE{9_&*g; zF%SSa005W(fEp14`QQDVxY$2^2xevgh>QE5{{NgNVEx~M_U~!pU;K-I@h|?xzxY2J ztjw%zJk0DoEUd)L+&s)2JRDsATiM(17jPMtuC9(eOicDJj7Fvo#%7Er4t7i)MvhD@ zjLb{`pP+}Mk%^6&E3vVeg_S)&)meKt6|t2mKb0njJhQx`sF|gel$W!as+WSAiI2 z(!aL2ySp>GvoSh2TQIS3b8|B>vof)=GB}%>Gq`x#yBc{g*t?MZRUl^OV&ZJ&=xXI) zPyD9P$k@Tnm7mnj&B~O=+{m26*wmDR!Ptn+l!1lC)QG{zl#PYKl#R`llY@ne)ttqc z^uG+WbNuh=|F@wa72xx*bL0_qHZyWH6Eku(6Lp#N3;rfs8|9`mt z=cHw3Z^}>QP9-Stx&j0Ou+Y#j&`_{2Ffed%u<(eONQejshB$HPs5xoqnOWG`*@>vQ`MFs67}?la!QkNF5D^e@k&tj%NeD<-|6{!N0BEq_ z?BK%?V59&z8W;o`*lQm^0DuAD;1FQ{%Sjsy90Cdw8V2@t8GwEJhYSF2e*-`$EIAr6 ztkgd|2;qg6Psmg-$Z5$kEhkuvEZG{Te`J1KWKg*Zq>#OK9nLKJ(i-Q6=ZDhlcvkd zGts}pJy7h9vgjHoTQfGQK90BZjQi53aPmq{WSqHXVzqEP*O;6rLL78!fHJ*BN4uFc zM^DaxeIkQDf%)_bbWPozZV2sOJRkXaOEE?x?RZmacT|#gy~}x^iubHDZ2!(PvC#C# z`Rw*+y>o^MJ?HziWD~cTu%uGVt?Tu{AF}TWSSsy`=w$k>=XW1&zP7sXjh`0{$C$ZMMVPDOx-`^(Hfy zg(u@lH+e}&z~zCZ%%qqu@yC8!wNexlcx|vQdtQnH zOVu$#WpfewCi{51H$&8i8TKRIWAn9>9NmUL-Yolcu&-y(=gvF+B|R%5Aq6#nzCnK9 zpS~2^w493V=;)0CGrDF|=Q+O>KYMv;!C;5RCaY}CM4ehHCLc=M$Yj;cd9?CIgT2ol z-(NlOSZZxbjbq>{BsEq=gVIL*T5G+0v-j-&<`5VWo9CLRUVNn^!$hb)f|v#cO#+il zA$CBM$h_QfS4Yg7p8M#D8t)K<5!a>r=5kWfy9GI6nrN?c0U$7k5|8rf6{t3SqX`)9 z6TAZIGoA^XyOfl6U~qCEtM-S5z9)N13g!S+4fC0!);AtX@&k(b6$4X(S^s$4Q0Qmt z@T~JAuk6?wP*TOHiXG&#^Kn=EKNEZBp85z%?mX$P_Ayw3GY0CIT@TV+o+V*GDU+|+ z9KW>Hyea(DJ$c{NoO`JNt#8=4i-y&K&R^Z(I__t6Z>Ej$mC5X^?&0Ds^&xhVzqDQx z;-s82jie|@RUSdgaOxgBjGIz1`; z*l}6CcsWhoir-&n4fZpl&5yb)!cizbgo-p_he~0^pkcLIHEkR%y%~je@d~JTb81~O zYLq8KE@^8_c~xpR3fq2c6bVhoS@rp|fx(Cvuk1Oy+$K1-obGYZQ$o>Y80t39!}6xs z&{WLNd8@1G-*gc%x`Lc|i^_EdcKZ6_KC{q?uC+JIpQZVw&>3T=VKv6{R{yn1cfa;s zR41bxXf8B0u&6G@i>c_-&Z1BC?zElyY(XU(Tl?Qo?7ReNYzR3ENgFe$%-y2!UcUl} zGg1s3xmM{4M@K{dtWz7IP9!4Ra9lz)x|qz=k-#f(X^;tx%wrhJ}T?f2_ZfikjLd?B33x{o8wb2Dp{@r`4E6$Y5PvuPx+-oq?o)1X#RnO7+9uv7<&2lG6_f0Vkqi4Q< zXLl(0D45&vSnLfma!;ztkUhz-SYr@0$NRWPqZf=F>g<+1%~Cyi&%46=f&{~p zsZ**kqT_zO|Bthvh-`7s38m|^nrHvu&dbo`3>7D~O&Mq15u`Zwd4P_=RqcyARpF1bNfl?R=wmGa@I zFMo~EEWGrsy%=xbH{jT*si}~UC8k3l?duyA4{f^rTPzYD++Ly&c)GSOH%PP_w7zOn zhgRl+A>>d_D?I)~LAyv+D&)10j#y1ANSMd)5QY=`nsmX{;t|?d*7e_Nyn;+TbE+8C z#0xFckJ|;+f1bF;lK1t^F%l*-cNoqp4gcLvG^zJ+uDh=Zpq9ta@adUtI(@gPtjk&DnbY zl=S|QOF8c@f`iL3Mo@|;pS~y+c1J>3RT+y#)(4#}(}u+jANT(%JwCs6y(`kPpdH0G z?N|t2^rNJ(2@B_&biPjBtYs@t;*t4W&%SLLm{G#~0TTxW#`0K>FLTYxo4!+hm$uJG zC2k4xMuw+tcF+^qeVfh>{aeF!oe#VJJSK6Re;?X4L};5q1s*9$rF zeoHu*k+t@ItM*Cey;7R+ABpDVaH*BX(kY;!tlsO+w>cqpUV69L*Y<6~X>br@$w`%B zDa6gi#+Ep{_5OLlH!eTfw`XD?TT&RN#?@noicmmeiwrg1Zv4I9yxzgsUWov0N)LkV zNbEpEASJH|tQhjSUHJ2^5D|mBAL?MoB=fddHH&&2r4chKC_rr4!R{6Khd{PdHMfgw0T23AdDFqjI({1#y{-?t4WL^J?ZJ%UbS2pd#4hoF53`7^9Zx~)U_S5;t z!1^DTgBW~2f5eG1v2dh|7ojWFk*cy*&iIa87yjd6)YfKf|9Ee#2YQxUt?7hvUDW{D{z`r8bpihk-M%QZ~I}}brb%}MB%1=!(Aa8nxUMGv0n4xL7n;A2)d9Q zPXq0#BQ{xjoC-A7z&(m> zmXKR=-fPlry)Y1@yxn$oc4jm0;$6X3XYjHZ*jA65U%DZ;M=gPYyklf9oUwZow}EK-%B~fZSdonuxYaf5!~~q)y07OVMLPjr#*=6NR;g z0Q3g{h!#AX1OT=i0Mg^7=@_z92yYSq=W{S$1Xoe|BV8Ylp%BV3F$7@GeKK=R)#!8H z#{Yh91A|JUwh#hf2lip96WDS9aOZ;@Vzs(pR{)3-Bq|if2J(3TKzeUOe>zzaboBxV8t`R|tvF-RKlIDdfrTwtRs0FbH40pR!)tEcL6z=vh20dN6Q>V}+Jg#d6ZItB`f+<*oEodKI3&X80+ z2QbtY3Io$_1AzV}1k@a;ffAViw{?Mpfcmp85P#OC3{6Z0GX?;xZQ#UVmGHj-;A5tM zn(kbrDF6oQ@rTSw`vHJAf7LeBf|CCUfPuczV$-LEQxyRKe)^>nc&zc5AplldF(d@k zg1!OZZLRgx*g)ObPXNq7c5hRurUpvaAK(zk9`#267+L^8bLKvk8e0pj0|4j_KaKYI z1M~o(srf;O+8-ML=(PPYg%AJ$t79`R;9H%#KY+mR(`pFNQrHj!NIX=0@IV~`0N`g! zrl+W=2Nt{yIdH!0%YhOre-q0lXF=wuvuXjr?8AG$ni?%EC?Np4STZ>UKmh*+Ko^~Z z8DeX_jq>mZGo-Hp!1S{m)k-i)3<2;?zMoM3;NJi!FV7(%0J;tUD)0SkY9QPG1ONaK z000}PRZw3fj;`4u#tDAhGFg*YJr5a2S{1rHH!H`NWJl;No z9X@uV+ksxP@D$|wu*~;;{+W0M89QlTMg${W+=Q_#4deG0`|41BE$4-Fm0$)#WXs|D zj+(;(^~@dBxrj>Mz5H@Kko&kpIi9}zD}d9(I(mj72!UtqGG_AAghAmx;uE4-=>$jg z=cg?O1a!koh4GvxYwmaJn$0~> zJ;o*{@B5wl#wKh2_lLm&o}2zxuUDYJY->O4Xh2WkYgdEW#xKqDh&Fz_#gWPf-l=5J zHqjmINQE=XwV2s~uY^gNAlJzBYWTC($n;bAvofBSPMlvE8I!ED!?g*M%zd<*36qRx z)wK!Zu;0$%fNuPjfd=bpa#mGtL?hX7R&GQ+$%qepM7_nuDo&cs5;hwjgn$y>kEi~ml*y`$*DwIzebVsM9n*zc=z12BSY%<)% zxc_`CBj=GWL2RkI@lxQ$JKi(m*~uj*%XE1RCoIwk!5FT3b00%*FKHDr>Ng+R0R!*ca&HmW6@ocg^$d;m3 ztdygGb)DmibB`Jp9o=75mE%m#8ctE%qJ&II#*2<$7(YO9D(z50A^z&)3tGJCJ>-CF z+%`<#fK1%BZ$2KaY}~`BX(^-B^&B3hY#hG}-h0JSP2K)n`c&x(kTh}8jmL!|#PYj_ zXe%@}&Qe|Z-66}!lyEsHsRemhGVqV_8F$K^0Xo+8$H=2h0$S;l&FBTTN_2|%ccOGC zQd@*hmN;`+%~n+`w7*g0eQKQwAY&Xf-g)lsWOlWW^ix<>XZUFiREBDIda9(cOY`+! zhN!fv74~&B+Dv0&+knzUFFo3aMD4j$i+(Qlm4)r#sYI$N!ExD*b@7la8~3ir-Y}0^ zNy}D25qzgE@{15C#*3?bXrZa{f4DXibkjAsFV!-0-^O)Yid!NxQ=&T$bu2AP)(+vQ zN~3|13RcT!++{VAhII_TZxG9G-X&7tB?w$=tJnyXsZ<~_ljydrz3jEO8+Z^LAivon zBtE6kRjrHUs-%^o#Ng`CEh~w`3@qJHw|WKmCzn@U`K#gD4uBaie4SH%=5a1{9Lt)o zW{Qbj)0xsLG~%nlNxw7cEBi`}&&=gHe-*>8dJvJgOMW97L~3jv6yudcg8966>-2t_ zM4})U^fM1##nqDPcj#I^+e!4vx6GoqWJPrqtD3b~#8n$9@lmLEF^~!J%1v4`3vUof z^psS@qr{;;3|x0D=!(g*oqVdx^eiOzPdE;F@8}2XtchFdFOPZw>zyId&AtelCryIe~?2O#=aRE zJbzUx)P{2rsn99yin$d~J-got>Sf^SE0>4N)f7keNHVjda6eF|FK1_8UY5Cp($`jF zpZV&uXUTDEN!O45!zWIqfz!28ro;fR8vC7#Jz0Jzf7@Ua^O;z@A{%`mPeEKl;1ml3 zGM{px3txnk;9Ar=Z7@V0!O5pp>vPgD3JP zf>Y2#OQ7I(l~78!3jAcajQ-_GM1aLgp48m_(i^kr#N$^8i(=F6g&HD)g51mFwjl^T zTcU@ls!VT1 z0Du~?C;jekJw#lZQ6znMH~%n3Mm~OFpcE0y|KnMNRqU4R8g>X{HF}neT;W1cDI%74 z$VY@#?(9v>))75RM)5}+&-=!f`@?2i4VfjQP;?el`YTrZ!*=NinI)qfcZS&{qZ&u~ zeG~+qi0Xn?fGeK;VH14%JMsQF8KuGl_Yu`)L^ALGU`6>L|C;vk0r{pVsy)Kl^J$ zCg%@Y4#ZYrJj=mtTK~ zcM|z&SMFZ5rIbE|r@4``Z2M{b)>hGy-p_3KX(qmUufWwPW*hjr@0(c>PC&!^Dv6nc|G2{ zyT_j7fpgq`-6(VM%JYQ6_AY(AZ!Q1)PI~+k_4=1u{!K;EHP&2@1FH}{BoiGyY)x*n&&wfOC<6($h2SsH5zQU!Ufr%mXft zG9tmLVv>&gbICw7E66r#D*~pI#Vn;EF*MzYqok}ghDzn>?Njcn&p zxmW??TBgh}DBz_0Vbs7ijjfcX7S`uqkRxy7CL^^A&tj53&{1DZ=8U$q;S71RV!5VXmB^uJ?J@t^$ODbtPl_{ z3U5Sbf?3`#P>(E2vJkUbuI7a6td7h_K%tH~ifkgcNnl%jJ5Dy6CW8J>NJJc+4H0`_ zw>p!**62i%NAa7H6WDyxas#y2GhrEe1qLrmzGZTu*~^iDQNXHmZZQcCk+L3j1PHJsC+{B|N$3ki@th~W z0>KYkOs@da^-JuZi&sEuUx3aYJ6`Ggikcf>;mlA)ibbt78;F zltr2!ZdhEWgrKj;Ot}XgAeL?Vmv5h@~5}7p-2gf!E{x;u_W^Y;wA@))8B=4~&?C;)kaa8CpyQNB0^sEA9!z#47ol zea0Mvh8I>~9h8*r+Jl<>GtNGC8W=Kv4yZ($}NZ<@Z)-)Jo z!}Dcyn|2;*-c~0+y>(pIZ$C<0fjoL@J!#?ED>@6Jbvat=UPhV3gf5~=>9u`n3 z`mCSQtu8v>g4DiWTvDY&j<%#G>Bvl$sHi1kmRLZC^ez1!d;CXV*6l|`j7QcC(3Ja! zRq!Ky~6(3*9iC~8nMF)uGm7?4B8pG_- z_6DKi)b1?7@3L3MShb-i-7M2|O?(MGu6IRGj6OTEMSAR_(wKSfkHOhaK^s=aip#eV4sG-p{XbcCLMa%Awx_{6b^mVT?@*Q^PXM{y$%j}g)Leh34>9z!j-Fb}S zFBCVudZhoTe_ji~(-Pg+p2X5hcje1#Sm45{5a0+c#$+;Na}c}Pmvap}2@Qac7gcs5 z+ksGombDA^61(}$U)kpH*bWVKEXT>sSU|p|#AZnwqA%Na^>Lm7JW;WuV4pUK@=!_O z7%4gIfSJOapKv`lh<)>ed@0{%Y<53I)5sqK=GHjx2d^R^)l^t~TjG}ov%m{=Mbs{m zeN%hfe+{yf(-m@sU?P$A+hUSo9zM0rtYJq?B_z-(jHZ|F1ydEg7n1v~lGq)Mg>{Td zUXYL$Y7Tn?DX(2;V`R!2Jd18wuv;8DVwcn=b`u5D=q~@_^i0-bW6e8(NuULtja9oF z*s(T;PcpiG*NovcQJqrbhln1JGD2UO-iLUoSjM1Tvl@g^_esgcBco}_qTtW!7PE{C z7PuqXaeDraOb+Mg)?u;hz;0k5GXIV5`RqhPe6`#^JN52}ht#Ub_K0GZ*g~t-fGZ^} zMR#VW{}QZ^PeId;ZJMh2^NHQ8UxuI5DgFfQtpHlxxec}}`);v*zlF|3zng_M%syy~Z8g z7s+?lcf#)a%I|CFtiH9$Y=Ft|`L1c&?80pNsV)L>$rSPaV&8TZl|IxmdfUU!PO^HmTqD3A$02;+2s4niX?I*s66HkFl3`4cj&S$} zRNVdy9X~d7=TQVBk`T;>hB#?HFVa~Z#$`*ZJ;sK>J+c=UQI(H6r_d{@t|e!F-?1|S zOf$v%(Gw%@?ApmNBTP;=ayo_lsQVW?>boKC#dFPMM~0GD=*Hv*pptryE0xmkR@F~< z&lwoai%^%{C%%cz#naA)kBG=$kv4Xsvzj|wl8LaFd`&c-kXu4Oc+_Y(7{l&7NLNIk zmKj!pf@CveVVwWq>3g^vI!H0ULjh{}+@+9`>_G5ncRySp$3{Zhqqg0mRQZ8}rTn;C z_yGgIYxD}`W(J!t-68qC8yqn{G+D z{j~7I%AZu2U8A}mH2iL6-|PDd9DI>er^675dd$D^cEy=`KZT(WZj;Zl7&5$}6vs8>I-%Dh@GV~eG%9`3eMS7I}v`9nNx=TYF`0#g+|(zKPzTyN=Eg;cK0xKE4nViueG zYG7OY%QV5sGii_HV#irVncqYNCpSfT!ZgZqwaoJ;^>BObmBq(lRb7311ibc}0L2uz za0$00?BF#Md@JuXsA4)L$N*n(25C>%rBfzM|JOZiRjDo=8mz6*-P^FWUR+wGNWfFB7F2 z$99*JyU-$CxcQXh$)QtUfl?MWZaO;iOtUTEBA&8)5d7q#ItN+sDT7;IHsnNgpyy(?LGLf$VHQJNpO=3yQt+3$}UPh=;@ zdp>8;NNQsj=1^%QeK4a4R|v{M6QMZKC_FwEQR=Wm zZn3P;NaM^6x5H22WSyQbQ_5KSrRk6!5L#t@E}qFlo<&DP3&lQ$&}gd1nHjG#u`VKq zpfE06W@_mpB?rPTs<34b#3XIx*a)@@EK;WDWrzUuW{Ox7vY%_a6BOhdnF9-3C6;n4 zRoDKjMwGTGUPgU~?MijDT#`Anje)}qr}~Kh3UFTa)K{-z_~NV))j#G{Mf6Shr|pk= z>TQm=C0TrlX55#N=iXe%u(!H0PV|IRz`uJ*`JaU}*dq+U8?;uRqGp&9)pfayj?m_< zTj+i;(h+o(zcX<4ov;shU|S}&u^DqU=j+DeKd-?&RH+w>&o~!5a*m`SRiEC=P{1P} zDyi1sDnMMY?>XI2A6~6$>d>1lS~2@5;;x+sV^{K$9W{s+zp6ZF_@_Hq-VLU zuGP#XGG3fE^ChNff&{h1lYOV1HQ%LzHY7C2nsdJr3n516? zEyWcH52d=VD#=JMc;$ZZ=B7}!0rk{RA`ytTC#=}Imj20VgS{ta?ev-n!Cx>v-g%bF zTVq7^D>-{__MLckMJn%jocOPI?s)_)raF#}w-nslk2E__?XGkvLxwY!t$^6h zxm!Ocm?1yG%cG*#UODCJ?wszF70cg&Vs#q6`U(WYQRp?|9sq%RmX|5%@(YUWS_}-W zbBVdqP#tpwQ+$cWMC@a(gNfhc((R%W{~7jlho@xil&t2K`%RA1ayYF(j#H0&jAXC& z;bFlGjcWw~Xwv~%e&E0?Aaz&&F?JMJUg4|l-4=en%-X8C#)?l8ies$)ZHHHkIkqLaw-GF8hyz+Ru9#}1I!y@kmv-YuR3nN}F za+~1_4W6D^P|8yk5*Db{l95S3Pm41gmLsM7G))4;rxX(K@WM?(K3on=2XJz>WD|9Y|DqBTfSljCWo*|tbsz-)r~<`Md>0MLGPkXTwKiWdsP`qlkw69 zP#d?H$mETUX4~#nFx=R|$Y!CKnR7;a6;ustTqJJ4&N}_7Wbb!ycTTs9dRuPJw!@+f z%g`H9wr~jJN@vd~?56mRb4n>EO^s#iG@D;PRes5QC0FG!87AC3?-UFBrtU&82p+je z;{?|wRN!E^z{E8L$0Izmq2N}?J3#1w4enpy@O>1KeNn|)+=vH-&ocN2a@utJTnJ6{ z{EUQ`yUsaH)8YZf%D1!Ag_okd@R3&i4)Fd!YDuVe1iwf z^BM*dcsuXxjG)8N>KtS9!3SOeOoodBT?mB~ykH=2-KG&WZMM8C;R`1DQKBv)BH~VG+5WOGZAG-8MGCW|7?-%WysLe# zG^e_Uuj;(m!yS`KC=%b%SbxB{*QR@ShR>S2TGG9I!ws*M(IKous5o5@HPqAHTxFON zr;5EZY-|O-UC)X_pjIl$;{C~RCghR096v=Us4U-=Epj|fb?!X$KyA2eA4Q{>=UeV> zFe*W+6^uv{2DBI^JjpCqZYlz4JFy_{&W_udY_1Z(^ zjJrh|-pj*#>s!I{3!3x+3JhsBI3LSOs05#;FmP&*x^?C*5~1~{YK4+rS;ad#I2t78JBF7x60@Awu6vQkNsGlr}$nNb!$s! zb*PD~I&~RNB)P|l=)S!D6Z1CD*y4-HW9~IClLb9$V$sQRkOkJYk&QL)xZ}Mp9#yl} z0miq(wd`HLHtI%cp1eX#?DbBMvoGlgyxQw7A;Uk1_}d1hxCp&#pC)d_zWIVCd^luQ zKn)8#Hitdq^X`9)(Q%84apbu*xsN^#9fs3HUs-;zNmn^i9(Am3%>3h1)Vj$E0dnW! zi^XH!WRjCxCJh*L!0Fw3Ph43El#;`*ix#4d)gLEIezt$~WS@qBsk(6WFzG6_AsfcT zs0LbT3J}qC?1iDj<>t)58_iN)ENdy^$#F7X=2g~h4z9_YpzjFvmvgt#a{gjHqmhxa zQQ8mEd_0+p92t&#Z)Nv3kvpkrATqz@|1qBK*d zEicnC)0I-U`ogZ}E)36uo`34!1DQw2I#E?hUP=XG%T~jKEOl-vn;M4Um+-$4TS3gn z2PxR>!%cLkYV|djQ=qwn8XCP9^q5mMtmBTe7`T219z}KFip9z0(-g0mh+p2yg!#cb z1slZDnnB>|sl*Bwa+WHlgiANA^idQ9PEnB0$Rp7qs9>>hGL(Rch?KuqaT}xwL3B6>^DK~=Z>Q zrvi!U)OF{KA5xLp?0$Xi3z3>^2Pl3eMm>5-vSCX>t5gxH9|)C-rqO$5BbGNa`cl|X z%4JWp+)~)+=t*)43yD#MG%|J}FXC28;FfY}Cbp+IO*BZvM{PT=Xisgf3ZY0`G>g&i zgm4(w#65EDEA6+WIm@+%tE~$K-P#h?3fW-IopvF#+7R^)y?@!4T8d!h0-w(~f+o5) zF_DH#lx1NTs9gpsQy7fT(^i^4k~ZvxAGV+>G?K^qQ(K$m57SBC(;-H!Cm(PToDN8l5{*Dp+n-G-MtTu=Pc2_77U>Gh^^FF?osb zXa$D$!)b0c4LN#BB@3dJmB|S9l!x&JhC?&p+KQDpsM)*)Og&JqH?j7p#tYPtWew~!wt!(CBV#A6Q))htwl_|dM1OL4qlj)zP!Aaq?uxvd-5 z8li&pjN>TtgVreTB12Rjg+`fmL~gBrl;ZFpXXcu^r<>SmlShiL|G^PM6Q9e6kuCZ#i>X*LZC zqQrC`)_d-TAcsiO_d<5Js7NAeLIQWLzEbJUJ37~9hPxhU<} z*K6N0Uac)ps2@d-?Ly~`T`%Yy@_l0hJC|Gjq3G1F7c#J{$Xr!!NTF5sy_{l4YUrMx zL|?`tzR%#c#r)y$*ev4HZ%3(f<(S!jxYiqLMN#g|x zT7BiVM1PcJr=LlNV{*B!Cu)bBYxIs@|Flcz2~~}^xh`Ng z_A-=L;5rlso6?2Nh{N_sq)AbDIMo|BTGe1Xc36FUaO7YKPfjsEar$PlS@btmAL;C! zj)tb|e0_RcGkEXRb}~Qo;_l5)uZRyr_C3uYB%6ak=XM>pi2)*Z=w=IyaR>5f!5~kh z;Z%#Ifo4#|1F5~Y8v6=E1HRR}^$zsQF*e3`YVpX_p4OqQ3sjhKH3@;{GOC?H4wVBd zB9SVKd5#>GV|CLyqJ89+n5akN0_~?2rTQ(E>=G4eSIKR=aOAUT@tcX){gSxh926tM z>8<-^SfVD z&?j*65Wng_KMH@z$GeRw$qx~w^B?^_#ki+7P@HyU!BbmGc@Kdf=J>L=hbQ0?PiO=_ zmj3wVX)2zwV|R;U^dfRVI%OyQen84SS#g||r;}_4kLd2p+_MQ;zR%7lVy)wgC<)2r zE%z<(p`^!G09QVlK3-SPb5xcDiB4-7L!W%+^VblxECl7yfKgiUMuL6G9vrir{gT_B ziekP*2>6&Z>EB|P5(R03Ei5JG_e^CRkV_XB^JwwrU3&wprW0AKrlnEp)!93EG^cvq z8K%kn#GlB>>81rzhKTy;%JE35w0{gC-k(ZHCtqgV4ag)uK3fjOWf>hw$R})f<>Lvc z#y&*A!P$$mlu`_yzPpnsHi>a4AwyrBT;{2DbwUYLJMUK?@MTdQFcH8PCykXVf`4lZ zRA?~6MA*OmRE0+sd+Uoct1$LYL7{zQ>|boh3=>}jr@=9fmHN{yP+{!GfXJ(D*?RWZJ4|3H{%qV)tOF*+jF?jo87N{04*v24h8`Z3G?=D=s$0Tf}x?3 zum~#~Ieq?3tQ4DD`+e&C7qifRzsE-M3XBMzXFpD4o36qZub#XD#;H8f*Frz1;_H1& z=0_$TY!z0e#XRk#{J5W_f}LWDo)yL)aXvm}hTk|DyN9fCX+OLIlFqMy;vp-2s!bU3 z#`oUaZTDATOeu;qS+D-LTF5J)O}NSF9Yy8kGa16W{Y-MgKmPMkFymP;;W_7c4gM9- zUQajbr%I*7zLNcswVeicPB1Dy6rhJU z8_OgiE20y%DRE}a9Wf%z!r3|w8mjC@Gw&{ST8mpXs-(|4R=8lnEi4IL<0$DU?~JA; zeaUG_OCpuSiGUMb{7xq#AFUK8{0iiVid{3{sg5Q}*;7{Sc*W&|zpGXzH`HEM%1oTH z8Va~@#`%&(gA{XPtPAUvycjGAmTER1kXicSfuKt=egpTmi3%TuZI}PJvK8-3_m1wb zzDa2Y&d%}cTG*gE1}U)*qQ+yBp7ICpMGnZ?B_MYMf?G1m9jITJU*ulYk_EoLaJ_tt zkuveMQs<0V^Am?DQuQ(#5lQFe-(KrGK&xBR7`ZpH=uyDAgTv+Klt*&o<8O(|C zC#5X>*cIgZ8z98eP`Tq7A-*rm|nFXs* zJZV#kZPS1(MP<11{w=|;FYfNnS-EUXp3_SFE50 z0<6^nQ@HxPNE}~Hkq22%DiUK5of;vr|IQf>Ohw82E=Ke1Z3WB3?M&L+3`x)RYDnaj z%4P02%qHczZe_pD?Gj;_xwc5vbmUPwt3<9?syMo}q%&iR{2brGFBP9XIX|w!)?|F3 zR}_i~tcXkcp0#nUc8eHH^hv##UBxR3I;cH(J?Vfz!bJw|!#q;VeoLicOjK_2Z+ZLD zlUzsCcNuBwX^mS>jC&UHY1`Zf4xo8V57y4Eg$fUwyYe08n_G0Un$unBA`XfK(^(!f zXMC_W9s}@fxMh_j3NuR8d=t%LE)j%_cVnf@&l*=Z?Z2%?ELF&_#I!{=RG7X`QAcE# z8$altCdBdtj~pczBBG=Qn+zylJ!(MMAN4gTcAJe$nLZcq?rk2{VLx* zeG;)xq?YZcZqWTR3fw00%mv2#lGiVE=?NL7{d3Q)BbWXu49eQKUym(>->>|H{7n4_ zQNC?1}o&)#tDF_V3z5SDwcwPIX7Rzs_yk)89V#g;aODG(N`e-A(6BslbKwoa^{?A9z3bbX%pR$ z$s$P7xI0WOcT1=*-XRWG)MV%LLLUu1R_%vNt;=e>JDaqfuF9%x*l5RFx~TFo&o`0{ zC6AN#*dccO)k_XO)<7;clW>jxanZt<(#|vF1-au|P2sn!%BNpiQ`pGP-hIN^ zv%8=Uj<#B&xI%a_Rnx7Tv)8yl`?S7^CA9Pnr>@-nA-C?9WBWPT|B%`(>(&=J-W}IP zXnY~&p>lL}ih^KtHSh^Tr^JNQok9;8P%u+=t}yt?8@D@Tv>Sy*8UJ(cW1;Rg&72}h z?U?z|=ysS*yaq;uV)-@NW8Y_&lJy@p4+$~D%(kUVO*CCu(e0F$*+v{bZmq~I@Daj=(!Sc&EDY()|F zzTlnsIiZIaZT-{~WO_5`;yvk?_mcWtWRFt+q9(_S^E2>4yfk|810&uO(PSh4xnIS^ z0m`xBAbO756a*X+BSwCfsZrw+cw0(=;rs9j_EQ7L|o}f zn9~nQL#2@Hp?OXOsVzsbIHhyE?`FtFt4r#3lf=&|F}es4&;>Z$^|BOKJ~DmWZ&8#v zv)q#R^Mp8Vm*d9NRpVirKo(fFA!zv{$$YwVYMmIIoE~>G6ig0zOzULPoibOoVC?~nm_gXJb(65 z73E@8UMkja16A5MpF1`atgeDIxSigQM(2R*MqHm1$@Tz(0|NjdqbGh-|8 zQJnZryNmRS{1W++>hQ1yJ0mllJiTx0$^6a~7}}IuMUYz4vQv*!s)~Y9 zJ%ZblT3&&GsebxA%?^x#_%F(Bc@hl)$ic1L8tQuF$M3|qZw*SR_{2s&qz<*;8kwAY zF=2K;>CsPKVY&YObGp7K198zKz>TVuZ)j14(h-q^PI5(l?nOk?5>rBRhS}1tn-;FPF}I|G85IkM9ZwjBK#2FQc&|Z+u~=o+B4j8r0UY9 zt_T4FP_1;ZbSxe0jvOveYUQyk+IV!zuG_oW1Yw+^Xz;~`@83G&3wd{^JUKhqhYQj$ z8%Qa>{a*kaK;yqwb-?IR;;bu);jf!Jw&KI`jc|dCns70xpADv|nWDwcWH>VD?@8B6 ztI}^xI8hvFl1L=wNfz|&8+@PK8%id3IN&^D;PnieXl4O~jx{Hr^7{VM^_|9DuLfM2I=lQbk)b0y7ws}lRHhCkX4Jz5l zClFsi=7~HyFp;L>JdB&kCZi^e#tkWp9c#{txQkuin3bmJ#D|8NNbXDU6dssp-{eFz zvtc_b<#=(6kapO{SW^(?6h`d1j`zrU%NKQcVPXQYTLYo#$_r<@dj#(;abwO=^s@l{FSD zdsCezDVAwxjR$E;r()YAONN^4%~MFths3dOrJ=@>q9!;Q7HfkZ1Wk0cFuUXBbrqzy zj*Vfeu6#MMiaug8u~(99f(bMj9h}>Lvcx;@w7vFeBc`UJ;%QDoAAxf-r6R_#c748A z5oKILX~2xQl#l#2>r=pC>Ok-+WYEFXR;93LEommC+(I~9=u8vM#w{_=HOZ|y(^ErB zQ_yaS3nqdc(W%-t`9Hs|(wlb#%Upk~P)f!L-dXX^JMNDrllh zmCp*BY+B2aX~79*TaBr6tu;E+9BCBoyL_MBQ(IU$JBuPtXr^WU5O+Y}u{_0WZ{X0> z<>81XTeSqWwxyn)#}evZnGV}>)X8#6P9gsQhP3EKi)37eLC8zlrIUo;+C^%fg+I|r zZAzQlHqA!5G|ft4c_yf|-alysHin4eb*{b+&$r5XG%s|A5^Y0MQ)w@&Zcly)LL2fK zHMu5rFhN|*oA*Qi03ucOD-LS4jZQ2!J~~5I?gYI=Vmu_50~Th!HkYW!`~6Lvc54EJ zdm~zd)rCrR-%S-J1GA_cRcBT4^o*XQ?7lMVeA%k`E7RMD zGj1FFjafFWSX!1i#>c*=7W?-cc2@YDfmzh6&)OyVQh_tS{EX)+G1!;YGU=r|KHn*Y zZztw0ViMH0{nCS26@jmTVv}QX7;?tZ!GaXy&`TRWfm`(D8~1-`Yx`KfkCCn1ZC^48 zH%X(z@Q%X5^k3<46O<;lR(uzp82YXHCO%O|)$|_mz@+W!I-`B`wZ-uwX6F9@X7GQP zCVs`L@7x?E)sKe8dz<|Yt0ms_7sHmjwS^%>cFRi45i5#w?{S^ysy@VJb%vM7c4lrA z3PlBvPGupqL7q8}Xc9zEFgd+BnI=TdPVcwMEhD|+B4)kh$9I}&->C0fi;4+iI&0zE zl{YO#wm}O_y`f@RCkqXb*v*EpBn)Zh%iwAhJmpUZiGll--y0 zj#{+MeQ-mgZQ5(uFX-@^k*1X1AaA)M2@|f}gu74pBwNgSj`)r<%_5qMaU%(mVWpkH zb6kqVp2G?VB$tei(vzc-(Ikf4Ok2Rj{eZC2@X~AC*K8fa6-lgwShF_$Kgo7FqL;%6 zk-l_PL-zW7qEaA2cR@GG;mE@6aJs2+2&WA@an$acqW7kaU`49D7lUyP?9-`rX1q0b z{6yH1K%Gr&tW0V=jFMel_B5Jxrfy7{(IYC4#UxzrDD3-up;hYMHWs=jY@F>Sb2=4X5 zx@>?5`1LhX)7^C7YF=o(MY6=BeJ9#(&IG| zgOwSnxTwxlyRfLN(`LO0;OWa35D}6g-`JFI1JjrEmb59sCi`OiUjmiN@I!)!=tZUF zn^wm4wI-dnZSMsWf^Fb&6xd9i%>?`SMbDlm zPvAQEg780vJA{Yo-_d!;yW0N%Oztz}wDpo+Uioaq=-(1hM=5hk>Gnox2U>SywC(bL zWcX2`>$DP6LrFv$7+GpyL~B1=G!B_8bf-TB)wGpjVVCrckx%l8V zqicmXZ&4+*ldfw7l%fJo83ri=E!K+%ZQJDi*9GABud1wTnnih>$0Rk~HM>wLq}xNz zM8|#P*(5!X(8FFsgnfiS$`V;@d}@@pC#^LVIgbM({tlFNUCP}bWX|e;7=uJ26J>`E zHYLm@ef%-$SNu!*(FrvxmW=Wmm%NlR|eZwI*j z7>Rw&wvdT;hN>EoVcvvZnvz`VNh+am;L>ef`jBO8CZOlNjC4a@M=hMLT0`hS z`m;>dZ6|Rim303Aj)XHfrUcV=Y4SD_gpnRpaMlr^)h>Z7nsdE94M$$rx5?S3&kxv9 z_r2hBYdn8KZM*EYpZlnuP?Ab&6h}xB4rfmdhRc|Akp`5?++39G)r8ZKvyvrhNx0VV z)y-dm=7%9BTaxfjHSjfZOnF249Ztq3iU`~yeLyr#5_kbqJ_mE#b#TAre!wHD!-d_f zdrDuVNQkwq!ocAR5sA}3<#c$la^Ut0BbtR~Z6IE9L|2)2fnEo~8sdNqb7@4jbCec+ z_un-O1gZN!z*BW}t}Wl2M?&+gS=!TmxDvQZ1QalUf7L> z;gim8hmnhVhJwVJa1%8*B!t_AWVR(`D=1gMj3N(2LV8NrP_QgAG^Q%akyDN7oKu>u z^{jYf!P+)?KXBSQT8p)aYut3sDHGdf+Wz`(0u8o9d$h^XfSc4m!}GGqR6mH zglK6_!L!Mk*zlIfbSVwi=$?WNyvPml?J=LAa#(V8_czAd?)31v|O8nApGW1>zd|Z4g zowsp$GvCS;>x}O+Iiq`3CO!4Z;o+YKwC7widgRd1c@&LbIxAygWOvC$jPx-7aq~j`I9j zq>mP8lVLZ(2}0|PmI*c3aUu^3iDF37`Ww-8rK6bSWmg#-B>Id@@-?8vjN4NXiNg@M zG|?{ng*&ejut~?bnBJ7;Iq2TxaS*SB{Rph3mOE1qW*?!C$Wic-GS4!5*WK(Ze3Egp z*xkHYdLk)rHc+tNCNmhlub2gsY>o=CByuTVy#>ibf=-qQ-AdqudJfnXxaMG!ALtO3 zi!CL&Xw$>GG!hre8kk;uZH9BQ{{VzF645PwOLOu}DbHZyTRCg=3a7?d&|-fgKHQ5X zKBB^7xV4BRQ?=u3ZDJJVDfGRMQG0Vbr8m4FoNK1&66(({ z6jk7`-M16K)>(-}7<UVHgSYCm`uC5j%IG;-!HSrL9Xnf17mZ1yH?ne-rg5MLrl`p4qfFy|K~ zu-hz=vfYDb;(iqqnPRR959J!2;Gaq4_r(&BG9)e+9&ulP;bP-7B(R&T*O8hjFfy49 z6PV(4kxtvJDSW%tgFTipqe-z?@Ig1 zym`}*vnaw6AGPnfH2o;l=S%2Z=vB6P#D19?Y~jCAw}6|R24eckXQD37 z=q=`Jfrmp`4cz+)sx(O0_FT)6FW4M@m+*9^+iU(D$8IfDl1oUD#>|R|;J@7x*VSZ) zJu!%-M6NN}DY>_$pmCh7Qy8^U$Vgic zXgVOtv~-VJUZcU&4BmnRd`YuX1^ZnluLM^~Dp8E73J|Mw6db~bvty)^r*Sih+F)fy z)G~yix2Y+f@69|8&lQS^uYr-VghuU2`==uQN6F=#L-9^XjurPL(cw#xJ$7NMbT8^K zGW(iiUp^D#>|ZU+=9~~ew-<0tE1BI*0V*kX-{{Y=2BfX_p z26ubJ(imfhx_Uk7G}i5F1QB8gBbfw1lhF{#Z0Px-SNj|vsecj^Y&|yp4rigVgcv6I zT?L#vKf#6AO^&+~{pkKf^jj}}<3E6p_WuA0{{VORZu-B0YOj#o@9Rw?{aZOf#FsDO zt4viS>In9xYG>#qyp>QTgiV;!a>hxM%zQNq`?7&r73wsL=E-!fkJD`SZY~Hy2Vl~PRi?Tl^WP!`$ln!s17Sj(IRrIE;&SH9qJC^m|jG$Zi z*7++>8j5g_UBT*qLrG8BfMbmyz_d3x#n1r$k*yw zrMihQy!Qr{F;?DTQj{B^s8KahYsbP`vyx!;ndu)aY9}v5Rw>wCs(GP$mJ4L-++9dm zmCpnh3#280s$9*@T;@-?b4)J{vsd90M9$@)i(cY_i-@8Mra7I9%*dT<%u5(!nS|TB z+*wOwY`xgK+z#TS%Lmy`kz$RV=|x89Zf@%lFyMB;l#QLSw(M~V>(91ZH~m4}*?rS8 z&4pQO2b=zw%%nZnn61m)!^(eh#N4HfR^Jc>({p|bOUAFP#Y+=|Yt%`p5O@pTv z%fx%>AyfwQa+QGIXm=3+EjMrlFhQBi6R@r`5#O3EVzY3d865Ztc5rH{DBdpv0vaXf zFdhs$W1*~On}Sqg&EBtFOxW?eCPz>6DlcW^mxjx3RH7m}a|!{^W}&0{RuDBU{t*

9RqvVQYa<*OSNGF%Me40vnxp(4sEYQnqPZIc|hP4Wxhho|G%9K{6DT^WX0nmI( ziYdVz6h%t9Qjm0*#rx!+o^_X7=&9I*?$hBh#sPvdhEv=y%65mih&1gFBnF~wW&YDf5`PNVcO8%xz@ zz`b0vUjz#BmENDa1)_qD)_R%0wc8shU%C5$&a*gwO`Vvi*-Q{eInx1Ej$zRcjQ;=y zpTUjp*?72N%uOX`^LoUn^;t>_ivAIUrRMw^gF#2Qwz$QJ{{VQRikb@c%dKJrm4+zX zXc)#@x6v`E<@d&1(N?bIN-PL!1sV&aXO?a7RsLPMf?bQ(_+k8T$ZG7*gyu15YU>!) zRCXPlSe1UO2XRdLQ5R(ion_;!8nB429pJL@wW|bqPCyx_J20c~qxq%)P{S&A{{Wde z{tztGHSzh1EJ_}pODp$&c!e;$hN^;D5EVg8z_lVwcyMaWZ8X%6(4gY4reO z1X5!mn)8q8)kZN@oV}N@%DF9oEFX*kAs#N6T;ern++Js7xhm`YU^1Aku~mAj{I!^j z-675_42JYUqcIjOV=3Qq)irtOL=U4e%%hn!i$}Jn zQZ5ork}ABiqbxM!nvo5#ceuP1i3f4UMWR=QOo5Jfa7I_!!>dbGKC@8%mFM`aYSGQpG8_I=QP{nBXDMi*_7IgCe02aJU$o~Kq z{7IeB#H-EJQ5Wc$OsbqEU0&QBL)Gh91*#u0jAC|%IQpJDW58K;wrM`utM|^xU5Q1- zKFI{nqR1Zd0IOY|vmUgiwL;*4KEf^Dc2SAok^cbJf`61|O3T!;RMB+_Gcobpfse++ z1|GVQ*Wz`Hr;DrwhfCuR>0Qbe=)3L~!dOd=7m7Kn&D>BsPH|BF1Uk?B9k3E^^nM`i zu4ZTT^+G5$2O!}9*#U(A0NtAvM#8D=_n)Y$Vp+1Y!*5cQU*#Kt;%+>vc}H{)aM}K- z8gA$af4IC61gU zEPT_Cs>MhD03lw(3F;Cn5+WvQI8Yn59c`Brid{DV31vQ>i=hM?k@3P6zG{JdFZ|f_ zsFOWLH6?-TMz@<2$lXEYhn<>27*Y7n=V+8?23p&zgoLlEcn2_X>T93I0Wu+8<`e$) z+x~88BZAY%@4_`XG%6BzMnCAS-rVgi(2K}Zn=v@O&Hj%M z;p#VGRiXPvLaHo#LRSffjL!}q^ARf^hZM}*?M>z>-SVy?FY?>GKtj65@pAtFg~ucV zgL{!%SEIo!6gDI&U4_Ep_Yhkhiw>BWWP4{;$k`405nhFVIRoqX_ z`;l_sPnU{mrk?4WL=}ixZdSQvAB7m#ZbBeEaNtssHXId*8yqRF^0$2?#3~EFYVxjC zm;5TnnAW(}H7+013jYAFFnGev3=d+<2ckDm9u(IT8Klc0D~71xd4P6{!mL_9BB0nO zH89RVJj{zLizbSO7hk!`we=(_)b@j$;!-K}%$CpdhFbm~d-WWX_n)|M=e!?0b*#G} zUw4wc`Yko?)^F&5X&E#W00*ETOG;TX5b5e_h#TqDHeP4P4;9ZB>{Ewa*O?=~zJX zNIIhl#1z;tIO^a#0eTVCDVrbf0xMw&x4vU4BB*;VQLK!Tu@KT)PKueMu4S{rB?t6* zfQe$$4qhe&jTAMgUM=5oZpwOq75*W3A8-|yeKLT}x0;3CuiU)suW%vpcFR}~Q+rlX zN*m@1)xJE-u5m7mP~Q**xn&IuRJTlR(`*G4Yq;zTH^c`bX}n4{5D=pA&~+&*=AoUh z@|fi{s)T&MP+gW|7DQ(U;}sSM0?ZkvnXte#e@gQmf6a`qTCK;vjXp`4>l_PfmA}Ka z$kzSE@9}gYCi;xkVhpst6DJGe7pHOHb>K}sJp3@9>afwi|rB95EHEX58inRr7KF^JgPld+BsJItV<_KIe|)WF?+ z%Krc>l$dSqa>ILzfJ?YTOX>=qW|O_kq^9_rQ%mugZw=z2I4{^tt``x7U0Xi)h<9V= zrW6+nfS{}W7-;^R5Bss7?k&`&quainW-;R`haSE%Cwqa`*Xa_PyQozb`<5?U)CD%W z;ud1Fv0`4zuTeT;JOZq}2HVrg9JQ=sTVQh$cxMvrUc6LGTh=alvZ4#C_X<~^%o6Mz z2`lRRm*%lV3L3Z?0#jDLh^gVsS{Cy&#WlRmX~J-b6=LPhOK$9@2ozI2OJPK%j%A~t zQj0md(~<(RQByk_uc=`g$A)rWk!6$sE3CmcV!G>aQNVd%wMQm(1^is2kLk1j0D}pN zj+~^<0LtgsL~f^#te8eyEN$8}^bke?p~*vJ(RsOdmpX1HsbW$KrS%rfZfBDCxn|Yk z8DObHFj+FK9%Yt}yXISAo65mzUOR{Q?q;be+zZV`0@p+fGW-z0@Am*y-XIB=F$Erq z%yKbbxnH4jP_oZOq3t463a+OEdXIK|%eL^S1NSk% zZ|%HDlwNBlSIW)>tLHcJ#vs=|@~7^nOK0f@1XtX!%L{jUZ*VIu_?u8-$<T zqc-(83Lgg&hO=Eo=?k>u%m%D@jVkf_mz5XlAw#&KgblzYjJhag6jS%qK;v4uZTXh> zU!7Q~zOraB)OZxcyJ}gs^$ZB{n~ADfb(Yd*6qy`F6MXLG#Vqq0B{%LDn;@#Rd{k(` z(0YjE;gr^`YWBvOti?48T#Z75ElO4(H@ggDa9HZjTtB5^`XzWQBGQ}|c8ccTtOFNn zzioy*OKIh0q!<_*>i>ZVw}V!rh)uTdTTBGuW3`I`jD z<^c%RHAE4ncho`RiA$_8v|dZR%!Y5o!R{4Pcgt8~fk!%)w>2*|F5($d2}5oIQ(8%W0r<=ot0y{#u&>k}maPbGc0`J_;_fqcQEiZff zMP-4Uo~9XatjiZC#4X7){{W;L80l~tc9&&-CT#~Bh-i=77iQZ1P2Zf&pt{Y#MqFi$ zQnV4+^R3I|bs9Kg3b*l786a+(_zPzt&Poa)<|3g|G%0}p0MG4;^f~HTyyuCcsyAAx zjNpS_-NlqupifbwWoqhGi+H(ED%=ah>M9rTln?U+TPpa13m}zVJ6UquR-l<|V^p0$s@8FcQ@N6-V}b&Lx`4)a zaI%y6c`@2TwBGqDt$C>!Mu8s71kA;!GI)?380Z2FhFX#(5vl5V=a$JJ+uBcf-R zG!A-VYnoOw8d`bc<}uYv5SgsX&99?OryMTxGdXLyYIcV#c+nP)S1E~;5i zpK(nK3t$?QiF%D{_X}E^#%9*0c$pUS+)b5=GIs=4m8`K*#~s1a>xdQ}Dhq$*7jEX8 zmeZQXV}&q4J-WnH%cCktDDEs%%9&u&Uky%|dl16vJ^vn{S&%GMt3)d%20A*;Nz!az1t z*&eR>oNp3=EH^j}dF->z86$|?cq5@@X|}2@8L_S=PY*Cr*>x=t`-^}z zP@;=*46qdLW;7(h*+j5a?dCM+cf&9^7kx`q&pDJ;;$>GiE6B$Z)b||zm6=3pjgU|X zY1;BbMACkU3s~ID(`iy|_-UfGK)F5{aAT@yymw+@#PPgkf0^A4+0^`EDR=J;S;76F>l;vCkT$}XGnJZdW? znrTb9d9|8aX>i8YjVvHdZxrA8iK=zJ?shKu`ik79-px9Ljbi=-^|cgmTP9r1LHuf6 zs4@D0LCeh3cbJA(moo1kULYGnNR6cM$DYEY^vL4l~GLUxYWA4bIL{4W9Cz<%%aN67t>RF z8B1Y95Fo)~hh7jo;$60}j7wF$GX%BIByND&vRWetWO`)JrCxqI*lhPHfbrfQJl2@W z^%4cpy`yw}vlZHL2XAq(0aDvF+-qw}n(r}k=Et~XfpXjw&l5tr98oE%;-WDZlFdN_ zh&HxkxRqr%mbM%7P)oyA1J;6Z{W7~mzvAt<>*j7=!{D}ODF~MHn59gA0WH#cin>ac zTzj&ifBS$4-evy)vI~{#3{%t03iN{9h%B$0QC)ZL>y|0T?KIF3dx%#=XCW_%ri_O6+<%gTE1m82AC#TrBz+_a}%Vl zp{fop2}CW=)iRYuDb36bL%aj=45|5*fXUe%p>R*>S(L|*;}u-X_`3(>j64SIxD|Jb zWjmY2_POp*9QsTf^99l2nemw2mSF6GYZ6`8aXjU?aLx+cR@S`0RXxk3j^hSrDByTG+ z+{P`bP2p4)u#BMw<#~P0r!NuRuRKZx#XU@&6$*P@RIyWuXCzh$?R5y{$<)Bn5|;ia z>G3uFFCWCbQHZ!%R~T7U6)4K9(EJQGWboZoBGB-~M>iU~skYLX4I5$#JY7uQGki_I zYn9GEVcoEGZmtB&e&c$5#_peF3UD2yQpRGURVD~ML~h==gF!@ZBz;U$hInQ{!OhtM z^g2qRbuAD5;tH<4#IYm^c9qsbQtu>jmA;w922)BGix$H<-uYwE6>KOBuS{QHJDz@KniCE7h z!Gz<)yF3GdRbnq@Jl-{5guI?kJsD=(#jgsw~@p+j%BI&7tRjNd$ zR#Rf3)*{ml&7L4t&Qh#s>yLc~T@mZks&TI!Y{ zdJYKH-WB3zs_^kIEa%j=@+;J*Rxm)^U`xE?45k44g;4FjrQI2lX#SUn_!MN#%heds zEQT6xGfk*kO0zg8+lQV5FrFC0djpuE#V}KEGVJGYqRzD~FzQ)YKT+Mdfy-B^b^hUM z)5lRltBQq=#LbtbUZ&$7eeJSb6xiMP;%5y%SeA)OzYRZ2mKmM=Zpe1dR93MHx(!ry!mbe4R%hl5umSIoaGr-z zOlBirb_ZdTnwFS+2QwH=+c`Qa0K|w`Zr>0GmRanSs;)ID(GtZ=U2<|U1x9kTOvP%k zB|vZHfy7dCJJ3&cH{z9dGQlXCsW!bb#>mJocJ7QSzb5n&S2~no$j!}AX3ZmdF-_CtMEtmQw&!qpx5>EJ?$H*|uoli{TkRUn zJe13RqenkK6|*ugd>tF6m84rnO2r($3u9*Hy3Kb#?0@E){8t3a{{Up!&ksNnk=Yt7 zXldV3YTjhm)i;xlWdi4m#A<_zl-(U%-}qcI{w1risAu%NM+n75vxu#klNM$&+gu&7 zNuCM?qyttA@5w6DtW-CZjcqOg)_Q`haRIN@%N9Q}igs&UGT*fG^;BV_L(qb_JJ%od zrShR&_T<|(NU}T6IkEo$7eLoSJd~uNyXF4?;}EMYis-shnDa8fz+*0-zYp;%w7=@r z>|ifu+nQRk=i1Jv5aJ|2MNfHuX~%c-3Z{3}do)kZy;BqQyv%a9*YMZ+kp=dS+fTPH z#H$@+$w3E(mSEgibrih!$1!+Beq&sU4ua@rzOGP%{$RFDlLjwi&3*|VoeMHyd|5Bu z*AXhMP_H7Tk#uoejYaF0B~TfJT>hON+xVIKr^kUB@?Nq_2MLPY+OFdP8%fYrTmJx4 zH+Z-l^Qhep%*-52B^V%Zv9+p*;QWh!!sAdgF_6D(wRYYI9EU*_(Q+o1RVQ z1Pil-EX`};Sw$Y^H6E-lZ!{Y%glH1^5t^4&L1xhcS%ZqdyG# zyDLlL3hK-jNqtHa;$W$_S221oxkL5$5d1^jk2rO&gBMB=&c1izDawWNM$HwDh?Xr2 zxV6d+9G*}^E%}P=V)s$1)9z4G>Qv+}@WXg-nq@bRP9n~kFgmjRVFXY!o@SBDm^>MR(cC#% z&C`f2{UQK^d`>)63&OR4^da|g&Q^_KCTfT3Yr461xvC}Fjxjvdy+yF2{{T_!YHeeI zfzc5E0PQ~`GM6P)OKcgFm94D z_?g<5T@fq{a+@o)7^Ra&o!R-q4+85D%3m;4O2AASmBho>F?!nOe@g0QBqfXjw7=jp z4{YE`S*02J?Z&|j3X3c@uUuc$7|%Q?8T>RyY-P|wJ3a@D5dZTf)UiA^IdY8Y`X z7sn8}XnKQ!_tOjK(rp{y+sPVUYqmAB?Ue2^t>b28*cY3C7%QhSt26HA0A011;jGU74PVY>3D@hc@`!#eAkN;RbyEf(j|87R>=pxAnjxW2$?sR|8aFf!*Eo^l)N0brdm!_rHn#_rcxWVfDTR2LQ1 zh!>tb%V^!!j^J*}Jj&@aH2#%@L>Pp(@q!I)T?g7HMcao7m{m(yPVDOLieYcA80ETp zWuljJWoF<9Bv)9&h|K+5+b$*yK&pCFK^;bnw{nPIW@D^ZT8VCdg2IgMXsSDcF!J3? z(-o?Nn@Xm9l>+fN0XKaRY^uhfT^vdZO=?vXOzLOE0L<06!~h06jaDiPf7A+T2(!9~ zVXRG_ijAt_;!=XEIm{Y!lD*1xztbzJm!m9&+~*iFth8pTGC0#)Io$}=z*~mOaHa>z z_LCO{GOA*n!N}db*)%(|)*)jIWjRDi?5LJ`!xy{&Ss^!vkaL~0X_Sd3NLvAzsnH-JyH7#fi4aZzU)o;uw zJh&jYH|h#8Lh58FtK#5YrU)3t2D28^7j(e9ceV>wRLy1jg5f?{lC1t_>BU17WykOi ze@g0Q+y05c3%5Jjjy+50jF^va(95f3ZsO>p5(Om~wP&47dp1j3r0N(&7;owp0`K!E zG?7cnLpBP>@M&xyBhHAEFIYjO-RCo1uej{8HObRcWm$I{LFsVrJwztu$PjkJZDr5if|Wn1ebJVYN}%2euh8{bz}vY$bLac z@o+D56arn|Y9EI;1=v4`cpM@;OsoRTe6#ufmDm0{E2I9I&2!W)qPqKYULkjsYj82h z#-gd$#LdBobYF{=SQgEzJ{a)f@4Ng(|sBdQy>Iei$V#}zaP+TtXYZn`CzC1?SNsUi;ty4;$gS{%&z$?#z$_Ry{PrWd6;gOU+{d z(XaJ!3nh=&FtP1(2EoY?)!7_ia|LV9@!yZ>SZ|~NWokYncN?kE%!Dax^l6Y>3l^ma zRt!h95R?}-++}5BXUhvhq~LF)nRn3`9&2Tj(=NGB~Iq2*3`5*d$jPGKq^z>N|xEsCccD(1-ef^b5ihsE3|zE<7m zIfaHp;Dzb8c&eGout7s#iRZ5Ph;Ij)j^U>N0Ht*Y#29wm(Wsqt>FKg0RX2$3o^>`bRWT`ES;~$dGXakJhL$8yq@i4p z`$|6!-b}C00Ip%`g3}bm5Ne3!)pCczxqt$CHc-V>5uEQO&lq>J5%DIUn~?72C4+du`LoLckgdMw~Q2tGU0_z5|H0 zSHl$(M|{kM%WbC-9FgkCXgUFMUT5=-b&MDFj(ijqf7NwBqscHo85^ zpiKAv>Qybc_Y%rRYz)c?Vwhu!&$XeQ2LL4%fAI?gq`Ok>Z)(r>MU1kL$?*aAa1o8M zkj1OKZmL>_z0WHLhFk(`qm1lfP#cR1{S=6xi?jCu=iHoBYYG>e_z4lDe9%x|G z8r!z#kfD1bAmoE9W)QOx&x2$cUS%6oLoD+JtO!re?`ztca2MhyDJCaqQIHn}l`ehw z@-wQCwMJ(yn(o6|tJ@PkN#WeV##e3#G=@w|y#8gJ)%P&Od|5~IuBDlE0{4AI^XrYl zr_8T^nfWX63)vLaD+qQU388=LkW#Z8+*c-`?}}}FDX1P+78Wr;@q#}rSLCH=Of50#oW-49o!0wT!<~NlC2`6mgYikv4NLX)n*yx)Fuzwv)ED4i)P5czX8y@SfthOVV)!D`B_=~@x?R!ZEVXXhH0bda zCkd|*3A8Vn$5QYVzv2|{L<>UQ`I#sl z;``*N2vGUVOQmUL>xoVnMCfz)mw*N>OyE6JEHo>q+G9r*3->?buv~uO&NBFhb5$)1 zP3zRlZR6@CW`x;^?yli$Wa?%?qxx4;nKH*sJl?Azt4(DVISG6$ZI}N5Ty^mc9@aT# z_1s)loxv8rQQprH!sLq2EC+N{M8N>!op%&le~7EcRf1sEXUxf5UgK7+RBfg4Ef8$x z2U%M_qr&*&RSxD(XF|&sf~8$A>IWH0Qsy7&94^MoiT?o8DXVJ`&~qtck8mqb(-zfM zH4Fn*bsc0E0~AVO=3p8}MrDar=5Nwx19x~~#g+3BjgV;mnZEEcszqhkO8D_r+%s{H z)W$kb5OHv=KM;0VPfSWzE~9&O+!7;VvZ3!J*;x9S6CtDKS&9|a%mssRrmZg-hTqoW zh)c{sRvGP|6O+tnlx`ZAb!5od3|}chihavXazM3=5VEPmp^8~yoOvT^ft@tRHn+?g zDzf*?p^B)=09?Qa9`^*O0^Wo#2s|3T$(5qRyM>CQE`QyGHT^57oO{OxW)|)s>tvow z%)V=xbN>L=Cfk?{w(hU>F4XfCx|Zql8Vb!27ykfrEq~VyZJNMp3b&|GtZMA~n;~-$XBUHDf0`lGu*AE`G5g;bGBLBu*mv_hFWD!wcW-MA|BuIA;J&SvJk6Cvtl z2T!SF==BVX>Nvr436tn9l1KWi+Y(^cn+n)f~)Z} z-fm`!^)H9Stc}s`4OFGv7fjAa?|;RbBh;iCn6xzqHqrT?I3r+A;%%vd z{580(RsAtTzqoFZ?j;c~F7*b5C8M#OP}dN<{UmC)K*~%*Ns?dY3=H*qs0AOT;tQWY zrFAH(YxE`jq{j7?QtaN`vc2-lVhih}`XhHZX94H+9AXQ0Ih(XA;%619Tsye$vUo{! zDC%bxi)Syyq)5HzP^-#8-8JG3OD`cuh*4`8lrb0mVkEq@<)$ca?pd@J?*uGnq9FyN z#ZJcWa-wGhrvnhT1iVDIUvldpZsWi42RLJxI}>u7w{rtr%Awp1QF&oiLh&*fG(V+v zD&`N@hIl%&Dypz+4p%iDe&TPc)7VW;7wTj}s^8Sl!^C_405dxXE!st{W(SF)k8ICT3E9*(yYo}4D&P#NXA~6yl;)Zr(z>2Z{V3Eu zZzD#ksqs5|d7LH;9av@5a1h9Z#h!k#GFZekzHTiQQ^}c0P^-=FGKJTu6F<%WEsWm2Fw>Rr{r^l=pA zQd#vI3Rpji>DZi8sp(t%R{{RscqKG~rx8`FQifPBPaaREy%c1?s zQKg_WE5w#Stqaw-g=%oQy=5vPyqQHU6eDKwg2E%Pppy%2Y4Jd~ORmN8vudatBGedA z38ht_gxorRlnr1)OXF48T-3I$u<=^fH!)y6g&u*>1cG3o=@PgY9ol~aLlkE>Za9_hjH#sC3ob?H`>1m?y25gmEBVW?7-^C4< zQlO(f`>rp#h>%~gJl#XdD5fpc^0&AbY|M(*NB~-w06@zYYMc8hHI*n!|=xulr{Vr3_X-#lqW{R>64A z+|V-GmA7NkQPB#jPjD9YHQd5xQRw#6OgZ-FzQ)1tMjjCCIaLCVQH z%(Hp*sOxw(<>R86+wy^(m*y3Y;%oX=S*W&zHLgA*ylFGxf^n$(pEmyh!=F-=t^)r6 zQ)j7SsXgGIf}de5Y$cnPE?dc&wpy%J$6B-8vsE2{m|`t%(K`)zI3>pvTnXW7TopQ6 z*H>D)fwjSKr%TLw!pg_2PUeL=Gi z#H0@wPc!MLWs@ugC|k#<{2Vp9c5cBOl5O%=s{;}hM?834dOHU32PxGfNkYfSY6vH*khB6+VN{Opf8JJ+Nf5| zOQbfTJOp)64GVi%;M5>1tX`jbjLSvYth;HRc+QL;q6Q>pz?+uxtEkA{Ii8nj$+99a zTJ*@)x2w;Ttwg|V%Kq45ecVWwd;5A-P9=+j8dkfn% z3GxC9u`t3_e3usS#Z?ikLO&b-08A=5FoO#rV$l??#4j+-sby5ebtCw=GXDUBa{mDR z+#5Wv?59axULC> z!#~#!mO54oNHp0jJP|95{xboQEAw#q#Lg4H`BITsIXB(Z+=~SFtTz*-DCWdJ>4`(! zU3?|(35mIRHdZRzkjz~%NHFBghSS9`vnHLuo+=Q>lJZ4*unSFPYeW$?0!tAChc?ws z!+A#=o@sE)pZQ<^0KH`tZ1ybC%^0uwj>)+=dbx7T`TqbAG0gt}jK+N+L)?jKjY0na zrU#p-;<4a&pR7`=43}&w>!@#V=*PdAzNE893o@c4wi!3qr#C3(v_fnB63EdGLm|N^ zsu?1|a&J=cVFU`)N-p-=SQiaK+#MNkM!9?xj>atCo{qkuEK`09YP(pMZf0!~jn|mp z{-8JuIf-e=3O!8M5e~x5Ty^ylt#M@1Rlv2&)+LL(uXiY+KIQP%$yMLfL)*VmYTJIu zg6x0{<9mz{P~bxi>f}SUqM3$mSQjY&0OFtu$NvDisVg)$rtfwbigIPAf8oAWxJTk}j&UpM^^-lMD1r^bfhA65wPB zhQr!Q_vl1_$;A}I+_hA!YT&sqRQ~`CA1Bl#{*(zut|Hgy6n)9`(Q@@^{vbS0F`6gl zm~}qS_X=_E!nMC7#1?#A zhnWNYMJd(*O)l1l{qPn68IsuEmFq?+`Ut|h9fjbJQWp6wq>Y} zVOd*-T42E&bW}VOu$e9uxOE~|Rq8#~7AYpw7&gZNQyBsu(d99Pa2P_U8I?*^4ZvEL zM2w)KCZ!CtKn@_4WTYCH3;=*+nw1K*FqJEv%92%pmbjZGYT#T%fkZ2D6ID}8B@~qb z0Kx(R)C5EZ{KV8qW&!|Z9F2b+VgCT+|HJ?&5dZ=K0tEyE00RL4000000003I5I_P0 zF)~2}AR#akGf)#FLty{f00;pB0RcY%^hxp_G>JT(Pb9j@B$7=el0@kwl1Vm&18~MD3LRgNhMVab(^MUi{Ij_wF`Bd zre=%S^sG?}wF`BdB+SuP2q20<1QAFef+++Ld`P0*X2>%%LbqG3bGnIt1Yy!``LlG# z_A?HP*u86Yo2DY}tv%88PSL#GvYa+#>d|ns@VN%vv%1l660B5qlztVwy(@acGcVD^G_rZ=tzPtbGC}#n?z@A6}r~V(>rLb*0zYw+ADRf|&S_axs{6lbStgHWNug^i3u9NhHA8D3nPj$oU+} z1QBHfGs)zZd8`pgArPq_@IU{=04EUu0s#XA0|5X60|5X4000000TB=}Kmr32Fd!i^ zK_W8~Lr`J=+5iXv0|5a)0O(3iELs~lkU}7W4kr_d#DWed6N$uv8O59##hhL)nrOzF zJ7J;?9uPqU5lA3{JQ)NKMPJIpRMA*;hC?Bc=+O*@dm)g>q%s-o_C+7c!$LG(zR4z& z;Vkw^EcSaO_u(UB`B-R1i}owlYW$zd!_!SQl1U_zYb29NCXz`clSlHf^pa@4Mz58I zsiS5WBUR%a{H!%aAL2%_(sRfcWfA=?dDRyObAk5u*9J`UJw!Zz>Typ>(B)sMq&`3~4> z#G6+hJGL6NHtsxkY&C9}WDr3fD1*@mNNFm&VXGdzq>^bgbX0;Skyxv?8u3FUL%I1z zSY8O!HibtAM5Fkgk3^D5G?sE@=_LOE%zYod Gpa0p_Lf`=a diff --git a/docs/assets/flight_controller/pixhawk6x/pixhawk_6x_internal_Architecture.png b/docs/assets/flight_controller/pixhawk6x/pixhawk_6x_internal_Architecture.png deleted file mode 100644 index 90bf35d4e7de522368f374aaadca6ad49e9ea173..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 775954 zcmbSz2UJsAw{Aia1R)|_frtnwh%}{>sEA0H-U&qksZymT6zK>eAiXF}dhaEnD_s!j zy@}LF3#7e)o^$Rw@BR0`|GQ(3!5%Qk9xJna-#6!8YllBkQ=p-`Oa%Y{XcQkm)C2%1 z`~d(m3CeQ-0O0#*n;ZZD0J>@_JOGpqvTXnW05aDHirSQvl$5@dPs0F!s{qA^_q9Du zxBMvl*>%QC$8$h=~NHSx_T(sMZ#wW zB)@f4^BVB&@JO7hm|s{=F!_`J=NFM~ z5`#y;t_SoV z_R2ojn!=weJ7@#;gFIV9)?+*g5$i)=hQ?kHUtxJ?po;`LG~H6RTepHRl^GrB^y(V! z;M{x%G<(0@QxJ)=tGxe6Nivz6}--=p6FP&i&g}{I$k_gQa^9fm`1Z@|49a_RZsr zG3Fo)X*cN}z>`v@)7Ssx;(xS~UuzZN=8!-avy$Ha{25^rB71GQ+h>B5;Ey&NxeNgL zQ=mu}fP44yWl1?mKmnmBxdqO>i~GPex&QWSvXr9zm4E_XeO#DYW_JA?~j^B4RK~s2A%8>nW*M5p55Z%9anvn4_F#lY+&_T0i5V0y>w)?mogd<(< zc*n&4M<)1#2+z3u&(eVFSA`t#SH1d`iGP(yn4sM6viK_-RmO4O`TS)qXmRJMQ6%Mn zTY&%g@+N@klN4HudE@$aF;q~P8tLKjV zWoL4*XRha!BY6R=2NbqJbuds^FrY#T67{M!+=f%yx{v9kQIIK;J#U;klwrgRWkexIp>7t6yh_=DR97L;BwoI%z)p?2Jp-hdq)X`0KopBqqo8= z;NMpJRtZJ1K>7<%_5>Tw{TG^WVP0b{jr|7HnUXaH1t44Mhv{PDirk& zbtZlcI~~#bdG~04;_W%i+&oDIw~*Pq4K)h#h5Nw*cn?%YE(8&Re6Y5U0!77O-fD&+ zFCtD10Q(ecpnkBJTPI%d4_v$oe~1gi2+xuHoeq{MlfVW*oRMy-Thh~qZ`!$T>!(gLeT+epf3Po z0Y~BdPdGU!g#O05zrti=-%E>sH>T2< zyxe>QeYqgO-j;J&XZ%$NyBP%r*bV$2`Ry+^1em`j@Efdl};ANrjU`5V!H!S25!)eZrUup9mZ zKSZm30(NW2%|If4Y)tHnkN$iDe^rf_zZm zg9z>@iUr^w1n{3b@g7eXsTBF0h$-)!)*H50&=gfs6!Pbv!~@QLm{CSts=vwn&X z6a$7DM@}F?1R&2aO55n40&|~V1}X9fcFA@2`~mJS5El`MEJhS=*w3Hn3VZ!i_{epi zW8UuBjV=0Z@jZ~kFL`yQTF=11$vF575tm3i75*8c4o|i-rFJG-|3XVLsH6?<7Qa7q z-D+zb_aY}Oh$toE>l7h_f_R !SYyC~$IeRNWNa6nj8S*hyOxE&K1!pVb`a-{T+a z3HSqVV(7qJkVn2z7#1`-tGkCct-ub@L}iwLPH0Y=3N|6fFV?TbHbMG_t~=TqcVFReJ%AnSr{>Y>_l!o_!64p#&G0k0SX0q?~`C%)f>tv#=NU`2A0w%KX@) z`u|5Rf70Yg(o&L%mE>sch2hMFmV!?}9~4-K<4nla*~pv$j9Q6PC+Hv8l;g%q`mt0Jo=rqY&guD^JcmLpG2P2h(QfycUfi8y%y67 z3asZlkq)Ra0)_c43WT9%@US>vd8SEDxX@U+g{d&Yg3yTzKcU~}T~qJR{1>pq5=r`J zR4$4@o=}-p{iH4PCg=EHF&G`i9bmCocBfEy589MJ+Z=@XRV)9C_JE7y1tW@Yy^%9O zmBy@j{P`m@kO}?e|1G}hpAmhz!dArpie3zQGMyLw3$F~S>V0??*K5==G{T?!s}=pz z>z-?Je@5~lE(%NWtGzrP@`PtG;iQMCFM_W@W?GgyxM(HcL`!U;J_S9YXGv1uGo_#^ z53L2@fCPW^ndl|~34<@3_ir&V`h} zRLD`-QP?ryziER15($55rM-@T;^l^OLS7>rt^~_>)$&on$G_x!n?J=K!1H(aa-d57 zSL5 zv<*L=A}J5O?Lvk4qgM|_{ku-{Z)pBomT z&O~5Xj{BMZKP&Z4+(*50Tz?E)0u)KZ|4ZkGh(Ip0e9sRcz&~u+_YU@U@AHd~URl!W z%nwti%e)2|d)`Zz$pumHZI$j`PXTnF`&-8RtG1NY9LVYGdfHS_)|6hkS|A2p*xg;% z;|ahflW~0NV;$tF)%N`|x0>504U3f)2wQ8Y-vXEg zTzErl4~Y3b$oy+W1G)DnwEvbM%O}8$%p_01F-4FUVz{;>+*XOYAV0s)ZzqwPHH-bE zEJ88GY0XgW#Qe9J1s??3dpOL+LIM5JuYzf#8OF{}E%n2k=hR^Q<)}=jL zMc-!ZN>G`-OwXd1S!ywm+nA|Ma*r>MF+B(H@w~);)^#le*JUu^&O~NdF{;B8^~;2q z{v3=f05i(AaQpEA1c+hdf{xVptPVv&v}b}4s(t@5lRmUj*ti^fHO`JSb;w(vZYI@8 z#p@(Eb}@Wi)^jd+-Gl|i@$^0}1Ve+qvLxQ=Bn?JxD-k~F08$fZJjeLi%qS*+aDQi^ zH0OmaQT6xX%RL{ZPklIW+%Kr>Uwidw>$K_-I`(B~YzPaeN4RVhv+jWlG%KeE|!` z^3CX(v;8$+GwWQq7ez8rtkP3tbiIo~xvfaygqrA&csL^SNVgm%7}6^UM^{Z&56#8R z%6pbLY#&U}4-GG?6X=$|npDst*!U2gUjCs;6#n9WfzcU8oC8x#)!x;@zkPWlbCam6 zH~uB5V!0r6RI(|ROM7#7H-D$}_F>b957+qk`SW#(-f1X4CtqD#d-T|hz%MOrG<)Cu z;6T&Eoc!7PQ)#M+HYCTwxfi7M0sl3Y3ux;Kpeq0{J)3#X%MNC)7OSz(Hh4MnnvqSv zP574XiwT??`ln9EgD+mA?s~(ooU@m^H9AgJ?^y4UHsK{we0u7ZKYhzvV`_95RHqn2 zt~6^!OH9PQeN3DjC~8no5won@WiHka{a|6uz_T9O3ykpQ*S&C>wNbxPDE5B1^n*E^&ZT?)(IUxl+d?=p(RiggNaLoXL>yd31aDMq&Z>& zp*Kg|wk6svd>twoF#4EP9%gH6`<&>gopVdTl`{(BLJ}f&r+9Tno zq%?1+OR~(nO^LlME}c^wEy1KB5`Kt8Wo#61LtICzSPB9XW>b5iE{DQdT@6?cv28zlWr8mr^D_%cp?^q@*D(r*95aiS+f zaI!f9t8~74enuvoIEiy3Nbi1e7e|a+cWn<(?snS=X1n_0zDRr*9cq0HZN|P&Vtg+* z-nu9RhxriB_g#y#6X1U~YMGhOp?VJhJ)vkkUW6G92~t~bNx0VexI)>suEcO{RKP?q z477;@RG;5F!Q7yWI8$GCT0#&3UCI`WXou2|F}y;cpbOy7oxDjfA>>0GIi{g$!5ZcS z7Vz5S=0Q+vORay7gFeuTPEpc|&QL0AJ*8?vck|PtH!n6APAiv`2vplFPXCyE;Niiv zy0WH$fMqISjde_v>5nHOBdC(UyTi*6iK>3M)aYW8-T^_CEV2;d_H9DwIw?Ft0t3Z? z(fmt#sTP+p0AChU%o}&yMlnG5{d+Ee7(eb>;KKKa2-ZEn8{~UJO|3Vdt6#`H~Rm9RgV$r38lf#+yRz^UG4NlfY-R9r1%01KdN1(adA=k8Bj0NQ5hLt?#5Qk2k)U;2#m7O$!L3JlW-H&|?p3-w2$D=; zC=Cz14Y>f@6I2f7??-ymO0(6C!mIRYg=Xh<|(E;eH`9k=ExahEdVAys%n zjJktRKJ;#nb+*b~96s6ndNXuXy_HA<3;cpz)I)kn52PZ^^rQ3Nvj}>Smn(`wB|L3A z>h98PZnXC~KAr%#Nr)a0-u=L^Mx0O`1wt=a6WPwAFK@U?w%1vO_PFTIa9|A&yPMPf zo5XZ!iwtH9UrS$59s2drh1q?zC`1$@N<6A=77f?T_5ZesRe9tbhvRmgpVl_gB-Q`w z)q(cz;2XFA6n}eaCvnvCWI{ZO#8dC!xHx%yWFz1A&Km%H5lqZ8sM_UtxBUFZsbCa| zXZfl6-csjsbY6w!4-5}7UANd!4vE{&w3#!araw}+ICw$VC-eifw}QY$0)^zWv{9bp9y#Fs$*dP!wMuxGc4 zf#^tdBs!IKIq|$%HefBG6*mtcG9MQ*v?uT5#}X?@lI%>n9a8{S!;^P1@ylf}oWQ!j3MCY0ORp87_|1X;TIaD1N=$`Fb#)xiY~X29@m9$Ar~YGe z22{tkcgM{Ekt*o5TdY%MPOS$_GwX6rWzVhC9?WB=5=lS9_JgJoIM>tteWKeOt)EZJ z5t}WpGS^?s;9N+ftoa~w^>;J9DNz+{Xro`b9$8t4CGkQHbisFzqEj^458+RcBhu7i zq1DzaG6+B`02X2^qsPcRTmw6$8V6?F>nfhww$$`AQWh;Su1TBo-FG)EUr@E3nR>js zs*}MBQX@);q&rNf*zB*pRyvuUYD}M+_P9|~o)Z9BS>U?K&ubJ+_?gTZ6nxz=pQMz+ zc)?4z+-H`!45!4u#@?R+S+w@}Lbdm0_s)67sWpF=+Ns`udOq_SVyu@j?t*O4e9`4( zG4j2xaf!aGq2q@koTLg$f51xMr(BaS^H3uC<@Yy1N0D6qMv? zs<*E%pOjWA@Z70)e7_t)J-%tJttKbfwANmD9AKp*RD^I%I&he+2nt^fzvI00G=?ha zcmZFTd~4_XYS2pJg}(LYsJ_J$9B`j}jk=$?$*~oM>G)-$=vXCSNf0VFu15L>`N50k zxfFB9fY;g!q^Uvh`amYA2^X0_BH2GEPU-QIl}mnSz*^sJ^tt;AMs|&N zfpzZ|t4z@?!Q6(II57W9X&dEbs}v}a#v8lsbuiaNZ9~uRlUrJ5PoB2pHIE17HK!RT ztQp8sid|EKJJ`*)J%5k=SouLI*W+Dao2)Ujgm}z(^U`Dfm4J`_EzfhNt0FO?1>{j! z`A*_s_6psR46Ek_nRBhc`G8&2ajXY|Nds_Yb)3?ZCKnLhpvJj;G;dw@m?(v4*&EVx zk1$$49vzfO9)#>aO%ZZbF;3Sm2tS<*?fYH;ZMnCb<*3{XEWcz+mjCa z!6aTh&vM*wa<$ekFTJA7#V?e-8R^uts_&8^V3hiOz6>cJBYQ$|?CsFA4~M)ws#~5K z|JwZ8YM@nmN1_|N)_f=B>43Tp%|i0L>UXI5 zDff|7;M}|$p3!a4AiwMI8Gh>UprOw(3kG%LRZWq&y@R#R@QYoWIlMQrO*1`|H#-8t zqFG7`O5L!F&PQWD9H%;F#5uRw)#~F6pEu*X{lS#sE%0TlQ!{jBPU&(DGtLgcPyQl` z__(Pjx**%PHCZebGx+1~=69%*K#mUw?wRIMs!vbd(y2MRGQqhgysJi~n>CfFmhK|q z_w#E^fv};T)@o!Q&8FB0a$UF3Pok*_tQ4%`~X zJ|v5Eo3bub)E=GKt$PJ{<3 zl6GnbdK}ovLFRFPe~=2+jbWDzo#EHXln=*w&WHZ2m80gw-ih;$k!^b#{<7)-Da%-T zgY%H*s3~IFf~#Su}<0SPwOZ=c!5Fim0akk@*s;{{RFf zNT>AVn9eY{683&PSbwZo3;m9(m?th}NVej$Dd!qM!>Z#a^qtCj#d(6pesN_)?w^@i za4~GJm%8i*8SI(M8{$xk7dt!j@bSDK{#5hR!uVRtKqT|pxg*${d1WHi`<+B7>7xaa zH4eh+u2;o*!58HY8H8i$Izx#UqJnID_RqUm3AtwA32U+$ zXh=BH7ePu4CFV~Plim5v1_hdsp{L$HY;W9~WAG(032Cz`w4kS}n!1iaV&7Udc)>F6Q`2!hfVY~Yplf6y2`0GJIsO{rP@deQ>QX&ddZUDdl zd>@NKp0fAd^-sTqQex$PZYqMu-#u>&P`A!4m_OvcmOW><$1&?Ns<#yX?0lZfVZuer zL{oPy&2?%itF7bPU$Rh~jYN-k{hnv4(P%g6%6Cv1?~?}+P!pF$Nw>+abpyrAWhDA= zL|yQ!Si5xMppV;T|JTzcYQ3QgtMfe~8`Ary{BhR?TJYCw>*jF;gWMdoI~naa{6lSJ z)MS4Ooqh(jvaZ7`lNNKHGfRSAR(;QfLU*QPVEEJHgb}IaqbZ!$Np*G@zDu@>{;jeY zF>y25OYVo?jly;5T|9Y9n-csA#}p%K{LRIo{LG(Uazd&mPTLd^$}!N-)PlazeSp&6`=uxbNz17oglQ*2$Q~J zKxmObuwU?*T;qB!XOGCeBADTQkWV1n+fV^iWwW`iybtg!q%;E~;-i3>Quv(V6(4)( z^%QUr4m{s8bo@CAJOMfiLPkYl(^Zf#IV_DN0HLx*Fn@_EYy9al^`$xXR39%rEa)!F z&ETp{A`&bw%h3N}aOZaJr~c3UIrcn3=0p96490Wdx;w==M-E0GqZ3+ECAVFTjEY8& zi!bS|l+9_=JSM=9IsR+oUo5+|WMoi630AIh9wL=y|xlS|!$KT{=EPp>YzGWD0_6-P#PF(aMDMwaM}WA>w*Dc9~|;$$6z!0jMmh!Dh|w1b|a zQCiBz-ksH9{@d2)sQl`r3{?uN58Z4}HoOmcB8I>1K=}B|)I5=q=**L4WT+kPn;<;$ zXwD9nBE0Nk*tp_%iU7@bxR{hIFpiZj`Kfwa=VI8+F6kp9f}&VO@5i>Ccxi(5;nTZ2 zyi{hB{YB1|71=!_-P`HS-~AIdgpVmaGf&{bUgn;I)Zdv8sP`B#RBQm+ty{G9R12}% z4|t+TB#yjyml%fON|KyUHMtSoHo6ZNN?i37>xKBbTDE;ZL+*)FJ>EThrLmGcRWoN8 zQ|sC%3Ga^RPa3J;@ku4o*PJ5k)+Cbib-n_K_1ZVk8evDjFpCS{#DaOAIS>e2^q?(m zgpUJ@k4eQ5b@m0eLg(jAjs<1>5!$2CtSYUFCX*AYbcxKyvD#F`hf2G0ps7q+*&7mF zFN=xbjuj_9D(BQ)-p1QdWa2^X$%$70B-19%C*gf90i+2?#Xq_<_z6QtY?7f_DXSoU zI8Gc+L>@VeJ5h9)Zd_h3VC#8Daw@^&p6MgP_AQ)bVl%YXqw}-l!0N#eH<@jr~}cAK559eKYm60GUYKF@Mln91+pSH*#5g z41wX%iPsyht{TjB&4;1ZH}Z%lQwh~iH$v66VGS?v<=VdO_?}3zr&vKL*cRw`dL#Bv2k72b&pr1?-`{FNE6>W z38XaF18(573cjEp-00;E-b}NS+?zSyHb#*P^9+$B z`e9Y2r8}>l$LB(yPLE7Hgq{AVn_UjAQ8hfh){Wf7etzkx+U-P)*QYL@^A4*U6J$I zZBTeH0-IVsRCm1vWppg2%PomaEY0fb(=9B!{tO*}-Hj6}asTRBH8E5OSYsHT6WG$f zd?!tq$`jI7Evkh|PTE9>`B%p~HwITUnByPu-RApHVfn*mNRgg?sVX%$U^>ae#~CYk z^Q8m(LIdH6C!H%>Dv5+m6f5psM|xi}TR%_I@vM{In5}x-$~=CtjE-&LC~`!ClGm@o zGHg$fY5s$X1Q{lBpZ6Yk0_sQzMtI)>5d9II5!YHs$p}E=Cn4g+Ku7!!Zewg+CXXtC z(%r-3NA-}}nstK5VCSRKHSwu0@^r;wI!qCpWUi++y#i}rhflu533MwcEoURkV!Rur zlRxg}-Qv`o>?TdiGpZCgb}g|wG5w@<_(u0usU|=Dp-ame2cfFiij9#WVe2ct1=F?` zvifywN`*JmSIWe55mChZAqL_B#c!@6wd|&8-3QaQ*tVgC>>MQe1P`1No_qJiaAmi- znS}4AK<>|%Ad)C9J^yZWzKbeZbd3~d>%Jjf7D$&-&}XIHE^oT?oh2R&kjxi zmkm2q?H)PwYzpGU?vt^dC~YD4@LdPr0*^~PzTWkBdVll$k9R-pP8jhgCy3M9^;jQ- z4fjNjAmrr<&H3${1g@LDs(uJ&e2d^BLHA6BT8{KPnPslQFBUgNjG%*>W@PZ#Z zQ>UY)0JSagKkL(#pan{MV|3?@k#JqW_#ft{LkL0%6U`@{0@P}nfq^7W{qdX)WBIjLU3#7Y{vY5cI&obyJ6pzlH_Wcp z*T0H5$+S1BbIjY8t{n}~Qu`oMN~DI8WaR%qPJqzDd!!iPuSa4YG_+6IUru@Pk!jz3 z`t^0-EBI;4q{ue*DtY-Y)vGNqJPFMepIf>!cz$btGj!*v{9e7p+xr~RnQq_Y&u?GB zynsF=_M07+!MshM54WWC9&7MO1)jcKJJiE`6J)&N8(|lBx(&{GrM=R>o1Avu87@gM zsltys_ql(ncojw%GK#!(y6(i$*f+%thHmZ$5d5|@LPvEHVL4ytB5*Y2h-*J%H|?=I zPWxK&r#|s%L9&EEhL(!;OpmqCD%GZ|%6Z|MGPmHbG>jUbdQuYW#(3YMkB767GzUma z{n_uTU;%2T>#rLO4;Ebs58=By_~}!@SVPz+OGWlFFlXm-75Ky+#}kVu9i^nh&;Ry{G_p$D*GT=1^wG2!C!m1Up$=y`~4OsTIEN0C@KA77!(4CZt3WyS~N zlPZJa@aeI!_moXCx>jpzYd-^5FBw+g

    pb3e3S(@QFd|5({%xTp4Y@X}Y@TNijA zZ^aDkf*zJk7WsJ1M}F$)@P@pdV7}_kGnd2-V{-&!Me0EBB6?z^t*x@EqN!|<{qCLBROK^z)d}p?%S}D4=QEL8w1j2a&vZvP zhO@1FQLxTBl(<7c`Otd13{;s15`Z@+wjDuB03Iar$744vEurGOp(n@h8BrOV$`7TK zyn89nubBU^+=>e$YhK)(*UHH~wraCGUI@j8kX2?937O?@M|s^#FS6^w6B5!mvAYet z-~-igtPcEM*{8Qj1ofO(4CGts$2chHvxO7#IqaGU;Rrl`MT5YzH}u>Z6BjR%)p|

    H#_UOuQ+4jrLGEn&o#*O>#f9c$xwpj`&D|KQ9{b6*RKHk6d~MMcj0^Wm3)E-nHr6fS z@WyECkaP(!7e7{1eQYI6H`z_~WoC)5*FwiO30rhS`c>5K%P|a{mLio^#kl{)3S;$# zrlxckm;IZ_@(Dlqm%c-R#3}QXNn= z`dCm9u63(ULq{heJ7tWl>`jR&c{v+zXhL;J7-PFWrQu15y{w81v+nEc2Z>~~aL6^R z!wSQq->ie%NRL|fknhp{0go{P|lRpBL@M;EQiihD>Y) zH2w2oKMb^ytH#vz_4P?oQ`0ufc{K6qM)xSxW##kh9{Gk~Znf>RV<^^!-e*8NWDqF) z-JP-ynap!=Ao7tEyn)J$UUDi864weU0vvhl7^_M9R;y2$$F)js9Zo-{;ZI&A`*I(2 z+>u7?$_H0`wQ5N`Z*P)%SA|GO+g#xIA$L91yS5^zJ?|Am;NtW=HvAf*qk6u2=uvl( zTW_NCsa0my=q{$#`#pR-Rt0OnUU%|l1FMhamAjpr?FYv@DJQZkr*vl^1|38tb9Wf( zU;|*WpQB~?a3&M7bm+GjCky!kaI65tbLv1j?kAKpZno?4Am+dhIk2m9y2dNvSJk8L zfVbuvn{hjQw;!qjz^2cKh<@N`RU3&ma{SSa+Pt)>i=Wj)E!I1^=1*(S}jUZ*Uiy@z#` zGn)O9K3*uYv9T$fsxSHLXz#EJ80MEQ{V{TLj`qTVhB^HGwL4gYMgD>^tijFM*;#o; z%VS+K8)#g+yS#yleeLMdv*Hx1gd&~*ueh$hXhXdy-dFdPmFXSknl%4rR2Q$I__JVk#W2C_L60orvB74|IOS655Z$g zgRvXEtJ%!4u6MtpnA-SYJTqJfNcV?pI}^Dm(_P}YVI)Q=N0t8%aGq; zr21on_y8?w@$-mApJ)V)SpqGFC%^l7*zzQ0!s#RBZO%VxK+^!_Ef>7~4n7g#w@VYUM> z_sR8T-zNgKr%Q*1?}Z=ZS*-{iC*}xDrd)dn%Mgp;Z!753ONwFd;_Z=69WTxL_D)s% zb3x|uoDWRO^2`NR8c zmU3F^qwQ`MsomYM(MJ8$tNYqGAgJ?n;l&nIqgcssD`SWD?bE*gH-+9cE%yE+5si-> z=4!2KXRQ)+4N7%J?iSg-e)>~;oOe7GW~?@w?hv0krY>ne?=C~8wi_LDozpFf#hhF9xCTBK&P;=M)&U$E- z4gU0;yUMJtA4Ds$J~Ls_g*}3D4Y|4>5uv0rUzgpK>0xi@#)xvE@!Enu^EF9GNU)Fb zo$8HP?=E>=Jq}dRIQ)nX8*)YjVnt^%Y5Pt{&=0R?ute`mo>Jh0*2z28y#kbg+kJp% zd!hGlX5nuOM0txwDQe29vAFAf*q=UP7TNB|*JkeK{i)#1z{9B}V>@#`o#wX^78c(F8 zmgDJ{Y3aXN(@wl}f^{|M(ItI+T}z-FIZ{rmlt~`QbE}?&BwJ3yH`k9JHKg{VwIrie zfm`B`(GAxoDr<`{% zPTA1ij0?vZ!jLJo4tAP+PdHWN@AHACDw7!)#-0Pm$w~{@yL#p#k<2ya9|I1Nw|P{t zk-aAp(cW&9udn6QR1Y;By1mqVX-6$=Qb-BY*rf6*Ij^c}5y5x2t~f+-!IsBW`n$iP zWkKxb&)Y_|4<{emjz6L;iV?*2zI;3Axjm($-Ay%qyA(V9<;$aB^5Ei~l4nbCie^0b zUgM2Yt-rT-#R}3QqZs}F*fFIJ0JE_+(q8yR@_g6{CD53H#?eLA9Le{ zDVS#HIw>%8jacDDHAI{orV4FkGrfQ0f3MaWT53cR6`cBgg0Yf%V>iX1y0uG3RG*6- z@`#_UD_^t9zLQGQp2IE_MA*-L8Tmx4eX?0=W%_Vf;jW5H;+|Kn)BNCdXOK?JTo9i@ zLNv`k&Q4#g5_q%9=Rc;Mjv8upZ1;*Sud8Q4QeDN<0G!-|O zWgKgqByyASIC0aS8sq$~aTnEmpGORKU$*zO0GpR96Pv^}&9`|8)>;65kzHWv`77ff z0)dqv;X!OoP#nP@Pp0yyvL#mDbl9fVJ$G3eG>GxpsUy^6Xth4ER@lI*r@!>-r}~aT zTW*4Ns1F9Qq{lIs`%IG~mlXJugL<4qFzf5bh7CUM{SxXkh_;^ad14LolFo50dgGhS zqOS3DNk&aJd-{4HAIv!dIj-%K=@#ksk)+uSdO1u5}hq=6+ zY`*=D?)b_qL#@Os8+F0_^1(q~#q{*9bFp^@KIjiD$A4aZR&4q#h9u_Cy#T9vsxF)8 z@3SfTV|>qF^XoeZbT*{b`717@G=5Q&vf&KK%_!r^NJz%)nmQh*oF??-xap=e+#rFcembvwVpS3oM=#W?8_kGjm))nfZEHmq=<$_ywOfKexc3kiYKb#Oq zGSR^QIMMLV*mBN?ou6~V6N9Oxq5CduTD*6Tk_v9H(AV(mTF9v@1Gk-w;1Zug+ssH|e6pjvPpcYlD&_Ym=#%L;3%`Hj zip~oHNv0jm*?}+LwPh%hmLz|n$J~PME;^|4*@;qex^=zujn8)awo*7>@3;>CI}y6# zD)_397cZ5b7l6-pK|RAAa@T2g>0*juu&vui2a`08hT>jDE;f5%9m{czgv&1CiHh1) zpO4v#`381&zktzL2oIu$N+)iqQW3wD_Ew3{YNQrflunELWU5kG`r-6$(b(>*@&gX7 ze93RAUx!R;?JEj9_(Sb1ABgdahZgF`8kw5rhJ9lRsF+fR(0A><6S$&7wO;Z%Romwk zSth!cfkygKTxK)srE8w8g->W-7wOQC}%lFj191<#?P^|`J z=X@2sH}*W`8GUe-lK22(*X&Y#yw=O2%PkL5_*eG<4i@d+G2wB~PY@CtOYhKume*F#Lm-a=6= z3`r=H_DAS&0S9M}$BmtZ2PB}agSoma!W*l%xW@QN4h{`Jf8@=0pIJeo&m`xKaPk2c z1CHu;@1BqM;w!O3orDG^c`bs=KBlx*9Qok8=DS|M3%exZg-DTJ*ZrwXSC~*8b8?iK z>DPYKe|h@&(-3h;oZO@E&BYQxblOnfcdds_h3;(Vp)7*>5f%&oDJyl5h1YD!LE+uD zXPp|B`P1>s;_#B2f$CU$8-(JwIkD9pH(dblD7YXBjNBZfTA03MS~hs+g_<#O<1*?4 zKuyNf0mJnDq9X2I?nPpo@iEA#wtl#mM)Z^V1U< zS|`@>uQ%S^%hycAj0h5UvtExs?GcAVJ@?fcyR9#pE@D@f%N}}C`m|^4fdu5v-ig7P z?)k}{on6RF#&4@LZUdkT)YBV(qWJt~k;=;(2|q$;u1L)8+8zAtL+Gu%SK}(an_0

    QR`xa1=T{?-rhK56MLhyfTR1hjBF1k0$notp7x^-Tly8`x z9lI~9BDU$>jMqj*tg`8LQ#DL{nN!o&f5ctmmOcBtxEpH<=NzWuw#R$unuwA)R!(TZlJar~({ADJHL zY^5&ed|-OEU#O#;obxPK=vdw;l_!9Ez#~|bg!(+2BKp>LtahJEF+_KTN`qev{dUx4 zGgnidI(BxhP*aINFmw9rM7_L8hlT=s-$p+5M$NdXraNLF@AS8j!CmMMAp zfu4>IO=MoA%@AoG0C^65LUnfB@$5`pjwr+*+LpPXUQbk8$Jgls6nfuyTI#0T@m}h% z>i3!Mu+=kPaW!#WpLy%=<||Xpt|_ZF+=0)6m#2&G75H3&zPa-ax_swb1>9Um$VF-> z%LD7@#Jh|ia@rr&j^6(?gh5;WyCT9WyA)v)(JxP9~*uh5Ic^QYR^x1ecnz` z&qdfD?QvP=Iw);OJeGKO8>zl30UzJwJD@jq;#pGR^UNr9uBtkE>ycxZmhY054@UOX z-S(joNkEb;@v~gMT^3NQ7uPRN~4%jhF7LKs( zBQ#;Ul*(F0dMRIet~)wDry2h$kX5{++iQ7PS)KiCT1-vLIO~(n?9+WSMWVn;{?~6N z6*xJbmOh4n21~4%J1)ggt*^fzC0DIXag{}t1SF)`n!a6WnCmvzrexb-CApL2>?7o5 z-2Jd7$M~BeMM>>gLGr5j6|pUug8Q}DF%s*OpG@(CwD)_-GIeUg%K|jtrqr8Fak@oo$MR0 zrOnhQ=<6G?i-iint=rGVlL@jQ`{ctW-%<3PdTIgI)jPJ5ebFrAg zqed8u>c1_2K;eU;1?TO!-F&6(sUDTQx?nB7yW4)#KPV=3%X!V$nkU_J=F9nTDuajR z4He;y^$?9MG3OZ;SS7b%1Kabu0reV^i5rqZWupeYSG=3&+&U6%P7Q*L1P$%??~MOU zcU|}U=D|G;4KLkq;KgsU&hH)Wjx^snL2R9jt{xY#^`wwUp`1kMtn<_)({^xebxYl; zr9fW;8>G5N+Na%@-%JDTem`|iA(_(Y4(&*+8j?tEMMI<3g;NjOssx+kFAeq__29^N zzcimvpR4&lbe&~Tn_su~kpe9gD8*W|lmdky1&TXGiWdt`aEce#Bvg>1#l5shad!=r zV!>K0xCe@aU)d zJCI>mWFT}*hU=v|`nc@J@N?B-M2sp!<1g=FfM!o-Vn{HAkYB^v`372ch494*(2CIL4%h z6t;jSr`U=?ePO^`5ho2dVe^z>V(u`ZFIntsW=4V_OHYMo*8<7S$UGzNS-~Iz`5kF7nM*5z z*C%2Obtk5&y#>FF9m*-jXvDmQ5FFNBu5Iny8dJ;tw^&d<@70pQpLax?n z>GK>DswD14{U;Tcx*!2C&+?x^K70M=6y7TxF?o76+`fDf-NPRX>`B4wftVq3BA3M_o;!w%_ha6pQpshQ0&*Y;J~Yrl=ObG z49Mk=zxzjx3iG(nP5B6UJq1XO!sXYk3!MQx3gQ)A|L!6SesRx;U~nzxan$;2mFo-g zmR9bi3+(~e?Q0*Y*dh_O(M!NfL7tw$qJiKK$Egp0_DY5ehBsUg@z+e{dy`f{}JdBs0VcVn`{%1buBYW{Z$fjcY8-;bKp;+XMUf9 zhlJS6X(uHn==w! zVL|{0JK>b~<<^xdo@^v_of&=u1tKV?eiwZ+N@NVYr6WGAX_4-7t{;Ctse-;byLQ^I zzVypyx9P(-F_!w3@N=2wmgf&!n?2*oYjW~Ie~)HYZZR~^;(hxTjE&%8?`0(8{Um5B zl!+3V6 zWDkS5y&^8?pSI|kx|iT;GQuSGK$q1~Q+Bak{fEjInhU$u-0PI@-QV#4HC`|nhW}mq z`EcP>QTNt88mcfn@!&#YLuOPV6Z(s2{VTOCj&kH^dhumc){k&`ABv?9)}hW%`%kh23s!=+PgZ-MUrT zDxfk?`&Wl?M&RSjnA?Z*JCCp_9bq>rf;U+9RW0bv$m**_#N6go{>>fmrkgT$&L=kUoB9m;yfb<*zd7PLyP%6IDai9={cnKeXRu~f4cPkm1Ff?^IIoTKv9bi+^y^$KPE9E zi2h-#=d@(;_Skykbo)wm(T8;D&VpyN0cACyveyXNZZ(c7$BHetwD#^~O>+o0;z`cD zi94Tvlu5NE996Y}ZGLWG9gWZr8}}(gj)0#yG;)N8M*K#~(_m_D^7@)Wi}lU;ikrC` z`>mCU0{sJg2I_RV(H(h>6Vma1nK}uE@GXBTK;5}auIR5UH&&&I>u^xkZ70KR6pmTr zhWO?&?mko(e;Tj^EyCkom4wf7G%k_;T48Y5x^@%H?{!`9-PqWSW)jDRpx{>eUNPn` zbHPOPJ)RW>iHz1RPE-$8*(|IOgIT`<=u6X2qq@4I^*MK1e$*P1+k}RC;24$|*Kfp9 zpCVkoqH=3GvE0jk`v-4sy$pXY9I$Kt$@p;lFn-4j1Y40XZq3n^=s%qw`o4odCLg=% zwd%%d{eXVBIsLIORfTE1Xq;_lIOh6(HF2>y%^T&-XRe#W79O>p+R=;4hhH2o@+1rN z$jiIWJ?iq>IL2&enk@M7yu;ntbfq(c9=9(TAOjcu_Zc~=X~#>$ z?89;SPi}slAL(684YlI$$>e{7{aMZQib98lqUbXWc}i3mFz68O_o}yx1AA5+q!BMu zqvEm&#tdT2jS~@N9{VVhtofIJ_C~$gnyNof%RRJK)r=u(jxtmmfh3!o4b7F8n-{Y& zq*as#t0r0W{;Dk!5WjXlrCM2N^zf+MMmEkEi}~l0w`5#giw!Dn}DG`|Ef+2(~ z_j~o@;9}icj<9&2V8s(Bz(B5K@u^5!q}kq<=9TL_-{k_JBJ)lF-Pn(@NZIsL^4$)* zOFLt&AhJd66$&$1r-M7XJY$&fONC4Ag~`FP{0Ma*@3*YyKn&Cv1VN67T3DJ|!@LQ;NC+Gq%uE!P7nY}i<&@s}mlMN%Znjo( zo2F!oV)Sva7`*NNB@U482Uq?_nsDHMgdyP#?^_sDbLHg{E+K55mq?xD@4=m0yneXv zpR?J2hOV>pJx$L-O!`j1R1}bBh{Lf2dqQp&6h&%7M!kdAe8x!9J?+T(hORt^_O(tjl&DH+L z)g1d0@|`%hKJ_dX)%RD=0cU-qpoVS;YhKt!-Pyq@zDO!i?m@KP_XB#O)f>9SNh})w zm+eZlg=+{_;!U~Ybv3<~X8&tFq6GgnWC=tV#t#Tj>CebYS7j)`bswk8{8i|D`_%pB zi32vfX@6JE+A`(frdITVu^Frnqxb_;x{X4s>xSLK$F}M9T-^QT6$g#Ozc{|PT`~&A zeW|{*9a%{8`*X=?usJI*U0eNrf3LZesk zZtc9uV#B-9Rx^;Kmw^fOX;A)8)z86;i^aHVU`I>=aL80=tG+y4Lt}m*Vf9t<$8p;N zeNap8tp2w2jtBk2RtP19`lpuZSie;mdWGh;{b%|8wvvXQ0!4jOm8X$!9jq3c<(AY`>3;Jyz}Jr|!z z=jP%pH~MENI4`mdB2$LBpOTTd&n)VE$|e-&D)skf%GAY)^Pb9ZIa{;EI2wgsl?}_N zczMc4?6K3r`$%m55Zd+mW@MHzTSbDr&jx>g&k&87OZDOFKd?F{OCVcpb5Jjgi)&h) zsWfUy@op&w-*BBIGD{ktGM_U3mKiB?nDr77S z9FwbZls=1Z;l78$1>FbrRc0aDTs$K>abswF<<#QUn(Y@KiMO5EXv4<}z2r9dxG;LMp7 zimFW+R&4Ue#f8H$&7>iaJ9(&7bMIT&ZGPSKKsw!T+uJD_&^$w1w1CjX2Il*b{kVtd zu8MPAbPKhCiyq%;?CK3ODd>0i-#f{*WC!n$Gs40sZvHS3KnN7V*>M+tre>7(ft_0H za_i5GKL%XJIOeKl&A^gLO;ce%pGmufM`+U*)Z`k{#g+q&$|?5|y!}-VG9RY4#h9G? zC1WLhJiS;K?rrk?CPNDqu<0-HA#3l?^1He(eKTsJuYBj>QS8H@v&?(C=1wan21XTbK1|yOLR$?t6}At9DA-?3 z*Az&s=>%=`0F`Z^KUl5Y+ z``X+?xZ5(y!0EK2-4#-J6)T}1JaVqNiE7k92sssGFLLiT(R$cfNX`Bgw)8a{I_!MN zSH(upCqH=e>GIyG=mzaC=je$C`Rh2UzJke2 zJ;w+}73sa<-&(&%Mcc>!Ky>#z0v#X>Cu(5iWMgj#3aOsVx$~ZJ$Gm=>2);CY;!Fd_!ybBO8z&0F4rZ+ikINo6*4%nF6bWVcGS%b$fJBGUQ@D9; z=_}r8$4a@rSlOF_l12q9>`C%+9kI%!Dd?w5i+*=3IRF>{3>davbFG~o_3Yqq*5(ZkggOiM)a_@i|HuIm(Mjahpy!Dfw+PYuhF`o3-CFY?xF!I^ek z1HRV2z!ZZ2cy1)iblbqc(CE_j^c@%L36SG`L>%&Ls>u>zlG;-bGvMynv%`&W0GYEo zJzQNkQpeK-@A1Rf#X@9TT9kPco3arV=Ci2f(Y;M4ZXl8gd1Du)Tn)Cg7{q*{PpTNU zXmIh#(Exgmv`2bF%qt#&sT z*s!9bfliM6!REe~mzyyvX4#MZ!ORgRo=xVfVThLNF5%vY^TXCo?&(|B4T@iknbeVk zVc{1f#}r48{*k$|m0Sl$Y7(NB$XfyRV{rBf^YKy#rM}zHoO+S$(OB~eO>q&;Xp1tp zU9(XpN1pS@SIg30Fp@M6U)0z0&vuKaW#+zmO{8C*6`;Ls{v}>#?B$|yUiasMUvs!xw*weQI9k8gHNi=ib}wqmmEDt_BM2L##=>-SO8nw%jPcO0XU3?>Sgf zM7|w=bHy|2J$gx-q_rX8)p?mv--H-f7uEp(G^(!Z6AO6gq1JZLl*6J<_gVSy!b3U6 z-NW^}K)eoBFcV7R2kY=0VjJ{B*USAnnHArB_45an*THehZhjssbU=3lKQe#LJnQj> zUFVTPI(EgEdbM%RDc>}rxGmuc($n<1SOju|J$5U}hd%o#YTz3H*o-S(>$=V0AAgO% zC&&{kT8C=kH6KGe2=_U$iE5=+e`{}N;?7e4W1Ygo%~IHW>~b~nBSh!Z$bhx&kt&4K ze(RNIL!-sGOw3~UPSL&Y7_4b$?PUpzx(IU|s}&=euo_|ReMlw_ify4b8;m`d{$!Ma zdN|PbifS$+LGs{d7Asw%uw5# zMKpR1dIWp1S?CRxqx5T;oS%|^l@I$1bNTt{`0TJF_HRibKANeOp*G|1sC|7+_~(8R zAbxgwmT$7Apx^`frRb$qU%S{DM@k!|WuFO6f4`%qK&2a6`VTv7`{cU5UPM)@+Po{~ zlZ~H--DCV=BH7!%NYaHma89}Z;;2f=m!8Q;^TMIDjb>MNlcLH8Dl1;5Fg2PfGisU= zK#|oRfZ|J&?x_9tnr2A3GA7wDJxpR2~P=i`3bLG(7zP0F=*E+^8iO_Jg056~xCZJ`YPPFm;uTO*TdL0ps5d zh3>{jyIPdQu)RSUdYrtpT(J5@LBy@IkTZNqq&~nMU^C-yMoG^gYI|s|iM|`QdbtDW z30w<(6gGHEeFzPQ^-iF@p&MDVa>A5H#1~0|H$&N1pMA{;-8233s0Qye{>jfVukOQN zzah8bsY~|GLOYLJRtH&UxfbmYSO#DRbX5)h!Q*N1ZDKaxY1^|t^cCU@rJE>+hfatYT0Z6`aDow~0C`prxEdt$ zLmcPXj?>JRN1e55C5c0C4D)@bv?F%&Rj|;@HqiA#PthcnO(6^SdFdG$2oHjszftaY zn8T&6mN5A9pj4#iuouHMW2Jcn=gT6%F; za?{~$Z6jzhb2ZcEy_N_V0JA#7*qi$^#@eDpcR8pXh1H5B(}pbXqnZKcVRd*t1oIRlGg4Y*UHyP{Ilg%!Hm z(SjBhYbh9E0(`mpg-Rgf6B8!9`4x0oX8q(-(yF-6a6dA3x82EpBM|JvY^B*)Q6aE) zn~{OX(JkBL# z@43e6rkCQQqw?&7z6yVS+7iFNm#z`xkfzz5|9RJdyEbA72}b6|fD^vLKCM-On&R3` zvjD%)&D&Lco@+UFk~E9{Xz^nmwVT@Asx0$VluE+bN07)-NArKQu1Z|szH z+pIS&xA6BaAkB($vle@1>g1$+U3MurURYbe$vvl zd#vxiD61*kb1=VJO(zd*FIn+1z1Db_8Yl8{&)jZ-v0P7%tQFI^ zj`52Nkh%AELYwE+nhGkh3Yp`ISG(-i!)I?Ez7&)pOV*}?2~~o6XOTRE@e;Lg2R5y=aM*t0mjPz%S6v>tCDf*!SRv>wp{Lf9%}r6d#^) z9*|vgF@x^8bU-eZvt?cMvV}KAq)+1-jQR03(A$r=;|WF=u9SQf3KbJh2WiYSq-7MD zw-{CdS>*wHHC;EXxqUi1WL$2qFlW6{6fOcOuthWf#hOWSir`Y~MtEwAERd8UY5u2* zqq=%Wd6GpRIl@l2F1I*_U?0RsS|&+jfABUbFJjdVQCT2Zon&EPzBh}ZSM}yf zY4fpe*gYjrs;Dtc?HQ3OZYT|p;HRgrb~m2!*ZykayU3N2!2!`>a;xe|^BbwS3_;2+ zwzSj=gr*6o#s7I$TlT8*U=dOC+Nx|F0Oq2;6!%*Aw*SCa`Yp$y-p$<+dc7nh$KUqqQ-J+{@abBq*+(HZZ+L|RzJyi7uxGI@2!lWQXxs* zL*wf&5lhXUo`w+QBOputckXHgc-*K; z?(qUB`u7AFdyty8;^o71v+o2MEWFV^g z=C|(rqqy_8@=Q8@Ilpzgp-ceX^7KVm=#7by9dwQaLLad53mwkbL$OBk&gSns#i7o_ z@c`HPB}J09`IjCGe(h(I0OOeTz*Q?np}Ld6^@70Gu$1X;db?z|Igw!#BU8l)%P1gC zvzXZ4dBHQ(mc7SXb{oKi-*(c61mKsGN$2$R_nU6rb~_CY{<1_s<}@9VA;V_VJ6Ff~ zqJS!m#7g<2+SbTSdUmrmyE@={y-%RqCik*9ki^8;MPxRodLgusYtXd&=9Q{uhVc4g zqwzR^H*dr=$)e=7O%)M$w-fk^gyCBbvv*u2@eE=$ELxMUdMj=q z)dDT%cp}pwr(HnVA3#|NQW}}*p)IYI&kFrnc6QE)|CZJn(>e33<9D}#sM#Ed!y~OK z?Ww6y?ktvW!-RHBZ5^P}<-ktsU-$f%BU%&a6FWwiRXsg@yC>sP*jVw+l^^MSyKUOZ z*x^@i(ArY*sw@_enL445AhWz9NX07nbM?i_KkHu(-92k-;Xs0pHZP;4w@;l}y`9!V zb0*=&hF6v~@o|&z<-w;~Ekp-2MFdp#6H+Z>MTxA?#&gKyUJ{l*<<+58Xz(ae+_B;8v~0)n;lfwj;~tl37Ek6GdYm zId`Z0W-|;nzF;}Xouy)I;>37J9ESA)(`l_nMzlH2_ zS=~nwLR0He>`IiBZo9|~yhcqoR;0>ewa0amjeeYtj_!BnAA89axN`)$L;D6esjeq! zHgij_?9G`1!{inOU!HI^dQXKkxZ;mm^^P2Lfet@1Rj z>2u{6K6+s6;Y({6vw zjcCdujTizTqA*k>^2`>c6aS2uAw zl#scJ*HOov1pn=xU4*>!NF|!9Jb4Ka6v1>oXG@g6dBAFt^C%7!*x3B15C(x;4gc+u z*NAN&{N$|<%aAy28?Ua`dCR?imlo~JuE8k%IkC`-`RPsu*`@MBxC7fj_vF{p@ylmA zEA}7IAN@JXt@F+qmP4-dz9;a+4C&=T9-?3q)|Q3puB56ZgYe9sWUeJl$i(@s9^?bJGhlODJs+Ig9J&j~3q{+&Bw_|?Z`0rxG{ye>-Bm88?8rphaiJi32IrqFUgc!Y@JG&e zQ}05(otmG{rwo!Q+@vxgLeWy6_gpJn4*p6b#FfRx#hQLE_%pwLF&Bxqz2(irCNsf5 z4B8&6zQ*#(*7R@8n;)Jlh)`W(Cb$mHKb+TH@QV%iojHr#az5svT7a_qcME@&|1$oC zZZ_T`=k3fM>D9=pHTkdA+S?@U>q&5zvtz`G|vkon7|@fUC7XDvY0Fg?V-spxhWWWg1wQ zS9E)Q2)&CyVjj$DM(m5vG`%maHMJQjlwZNJ?*X@Jiijs1NotGg(s3`b^cxn4hYa=BH`OK> ze=1PL(|$A6N@(HCz+^yGI=BClwT8Zc^9C0CdSSmnlaF_E;b)KYs2RV{&9X>+FYL-><>b#ZFwiI+OrRq;BV*iubFha}=l4+n`_UJ%d)FAP(GrVMO{!pd&Hl zWlx;L#j8LSuDb(26avJ)QqhzT$#Oflc%!WJy>#;-gjPZ8#e8WErGcOzoLR_z-eqIF z+c*=+Tiy~`LEB_6xqN#{#82ZL?;!{MD25l0rCrZVU6<=#p-ZBbQ{Jj>HX8g9@irUR zw9vrtyL?1W2?BX*wx#>Hat+LJhgLFN zQ5VHxvUiohB&L?sz9OzZDZTIa+oIXs$icnA;PfGD=*@6vbjHjtcdd-M6BYadWQl07 z^haX9EwHtw0-wOrBwm6lWio{eNd;^e*H=pwB;;DAS%f|drx`P^C$BtGSq8p$L`r<+jD z3@C5xD;PiUeZ4|h?$}>F{WDFvUM{yfXfT06S75n(k`3@PDUs8`j-~{XZr(wXU_Sj| zw5syPo6B zfAxbUbynY}O{m|R+kd0N$A@PQrJMX1D@r4t(4SZ>ctl&hGGN{i)6A=oHkrDT7HiOT zt9osnMw)#cp+Ni8RGyZrx={~3@JSdiu6eJz=#e?AhpQZOf^lm5k~htaB!2cw^JVUW znLB_t$JcB|K*fWtqOAC^;UaF2kK<>XKyqZeV)rKYZW{pdv^j%mpdNO>8M7u2#Klk+ z7gEwx5Bqhq0mGa#W)0r+v-EUE22-9g{Ri7ggq-XpVch?gC;e~GTym*vvL=U+g9~SKER~O zkeWKmHCmk`9#LaaVIb+X<2MP;tv79M*WWZUcPf)R@Kk<~eR@>!B@d7eE#3Pa5b#z6 z*sQPpBqJ?0#ZdQC6mF_oQpXE1s zV(fbgbhW?!{K4e)q2WZPE~OjruiuFNR$cSQTx&>4+MKSrYdSXDIkVj(GH!-9*-=5N z2hT(rs5F#w zR`LdMgmdXM6oJ!k$;l%$FJ6X?_z1e&)vX0S7(mC%Wssk#I>w4 ziooe6ZPrpz59aw)U!nocsV}!!bCWy2xxPd)hU~rCKm7H-p${+O1itv+r|sEpR*af{ zcvqU@aqc(T)sEN@TlRlpT$B`^5y-1ej_kS+{|gBE4+Qhyh=a9Xs@6!J!y5J3(+C}m z*4z9pY_b17u#H+z#jMN?9rE%0-Q(x94sQG6#vT3xsu_Qzc5){)5q##Ye_5{?@~_GK<+c#S!-UudO&jxl|h)mD~%i zazQgqZq^Hzor!5{mz9d>q9qaT_Yu>Bx9o>dZ+zkodl2sZ|2&dtCKSFAh$~T8|Nk*- zwWi-1JebA!p^4b}^C!R&akqj$`fqVi?8+U@l!NyDu%@kUXCQEPAylh=0H{^}Z1Jwc zNb?tgPc8GAzBc?lECZQ@p`=cxqvFJ5?DvCg62J$9)EAk=qQsHJ_vhFc?zty8+G{N* zhm=)=Ybr-8m(I<%@g3*O(L;N#iKwI{cT7AQU~*J)v;GUol3z*4vM@T+VQOBGQmp;*TEi(ov(w2)sj^M zNEmzL@B|Wo&Wia03!nq~LNkKc- z6Df1?qdMG`KpGvsU0Wd^bQC_QyPtjAxKYOuarJxJd)_%ER1);~eVn4&6V5L*Lw6nS zh!9bS-ob*`_F=cyTjj?ZasE!ll!d3h1DuPmzOsKE;k*8LK;57)ihFV0cR+m_@&(by zLcJCAWRO^jEvO=a?C{=^RR~7Z(d0#-Ioy=^qv>AcuV%PwVg57rebllCubGuT#eE+Lvju z3%FngzvnQUv46F8zI`Aze}_7iKCM@tUE%l>F0`|iEGY)hiB3=(xDFwhex89DM#q^m z{T&g+-et%E`x~DV1-}2Yg>$^D4Rs2A9urt>{=?n97+eFkf<98T@P6Cb-mM?$#0DT^ zPV-Jk^bO11++<^oS#wq(?_p)HqKZk`PIGJM z=Ll0Rg7$t-5!O}Mz0z8gZLD_Pb~6#oLY>u4_ix=Hy}@9y89e!rj-8)X?|!F_lPZ#EQP-zr4Xk9D;o8U=5`%2= z)1&fv4}b;!{_A~^qIczwdG^$yo=Z%8yhzB_Jwu|M(_aA# zO1Z?r;F0~sLO<{bHX9|j=oaT*uP}jI8=GfuBwss>8`SkoI~-G#*wKW*B*=6II5(4a z)N@jJ{|Vl|qImuOfUKT<2=e6Lo3*h?YIhs&utN$`im0@}K<&#=6BCo-_5+EFp^^F0 zzIkv+_sPkK(4*JP44Fu<;s|6J0VxXGDugvyb_5j5;(ykp?n`*yeH2n{N|$qc3$B-! zH>n=F3U+qx0F%#LQV^gt4KfB!yn=#?wC}#A-p!LH{S~X89s0!Tc{;Ph;_M>fY*&3} zP{k-f=*3Zpi+3-w z1}1JYkFnMLo>~9WI#0%{kgp)J?s#y6+@NblqT|w@*UomXF}=cyeOzT7HeiK+D!-q80zK0at5&N+Wu zi6MOog$e0CW>?5+0B>EU+^S>q&(DeH6`b&yh^S8a?TaUaWK!}&$4Uv*SS+!We8{sw zb%F`4ny?>B#)8w`-77w4Lv(zE=<6{bA|Fvas z0uA}x8;g$m`H@(Y1ADhWmK>cZt)>s2?)k$zl_B3qn@`y!!v<{>t_h!uk2vG97J#sk z4_OnQ^r)yR3gG*i(jgZa0?>5pZMM#U6Ts{#7f-v z`F;c5I4&8f+vFK(c2B_HPJrv<5)#CY8Y_Tuq1%o~<7MHFx6_%GiB_l4m1%^2at40N z^KY&u$0ZOZBk}ttBvuHvyU@P9Ii;#sqlXm8o$1sQ!bH6g+pN$`u>B`ZnqguCCpsms$Mg8n$ECwRi8A` zvOZ1!m&kjbny&17Wx}nG7XUO;>%QOKhcU}Xp0F}B)Bc4 zZCQ=6o4K^=o1{_q^he8fQXu9!Apxq0^klO!Tu)|f=L=`%@*bo2IGRiNzUW5F8OtLD zse{fs5Zb(;o{x%*q$H4eq}CMLW7Ot-U($%ofz=~s6W;h)UvU@6imJ`Ta8CF=@6=~& zVEH3jI@*mGCR@xV5q{zQEWZSK+Guox^u_!~T4VbOu~{YSUSAZT(H0%T9KVAkC_(>K zmr&2MJ3!Z{mFoXpm;9?hsUZuN8$DJ`AX`!1e2+n1iiBRqy>C@QnvmcM8o>v3JY$oW zQ~9_{pS?4{Rj5rOAN^6Np{w=DIuVMrm?+>c_o8)g8)2E)a0SKlr8G)(GaZbd!YH7& z^_(QEZzI^nySqt^bV&Tc-1~!80?gTZVf@o6V@ax5RIeWRg$u(ULPzEb$0zojY*bX1 z^abaLA%Sl?>-yh?GsvQ*lNeh`%J_p7n|rqs{a?gY38znZE-wAv`$0q{yU5Z*XlFlP z>Sj!gz?jc?_aNU$lJTRJPZhz$$fysMD##Dnqz9c$p^(-MxfbUL;MC!;4%WB0W~pXD+Af zI_0-9!ZnFr-}mk1*)<`_H_tE4PJT(xf`@AGS;UggPFtgKQSY48_*e~gkJJFHKG$Wf zaLDuP@Bb0ddiEf|IdLG#Vs$P=DLi1YGJuEY2b@+<*5fG9)z#c}?byc`t9BWM|BHTH z^lEoRiul07!a{K0;HpUAgC9)WYhB)kr$KnjG_4L!=wU2uksT z*^F=R-?6lApSkQJY2g2yjLC9doe%FmJf;A4lD!8;xb)bXU`SIbnK$4c0AEmiiCxuH z;2aaijqK${VvmX8{pP{tsDbzp#z$tp*Q9>;C6~&Bi6s#{9`w4>OO>S^zED_+HIPi9 zdd#v0%Cpo0YAiHH-K8#yeGV9qShe=|f{i9wSD*99G#DjW7oc30#4xy0Vc8cn4m zTFVn$)NKogt7&qoDbMESg67l5M9V>RJ>h0Xy`EBCdcfZ;V#hW;wzaIBEdb|wr7cv` zy}KXUx9CZg2V(<%iJLJ}ybTwQXCYYTK}z>XCP<<(k`HwD{Ifg5Bi3 z#{MH;QKHH26SQz*w%P0_OfExth`jTULulZuXxQKab6K3;fU{R(3aXI#y{y8?&Cn_5 zAiGp|(7QYJ&{3T5_22<}19TL3tVDD1(3;)TTH0zhefxg9j;?N63J;smU_u_hdLkR+ zC~In!uipIfioW356f!0MYJT$LOoO7pi$H(JI(N-63d^Mhx;qS`#B11l(_%dh<}4}K z{%&rCgeeCjyNg;=}-QRHmt$Hgg)nQ)}{66w|p^&w0iOuk?I4Lqi^t}sast+ zJG0@9yoRrM!|)A>!1v}{FjmL%McM`hf!7|W%&sExIvrM)MQ_ZzG~7bYD`%mJCvOW2 ze8mKXYV1RMmgU>GYpXQv7S)>a0|=}7-jKnJZ_PL9W(Ns#?mbba|4eNh+K{ zRSb!lVgM9z3B4eDMiBTM>cV3b4i>I>JHn;?)s8oo*JA%mVzv)Igl};%4NY-b_Ud?4 zq{WzYc4;=#~ z2aD7zkh)ZO%bK5dCuzR$c*zy-+UcYh>Pwj~!31ZxKVy1VNZM^dfJTJ3qrKUE>531!=qb*L1CSmR{DtELHkDDtP6piNrtXOrV%~1+E9MFfxjXDmp@at=@byxdM}~i zl`cu+SjvWGZ-@9~x6lFY@o(wyS#xXmYg`zt$7X@-`u&WArVsIw!2{+@V23xw-Yu!k zFo}EfszIKi-h%6##c6_OUciv_SH{)>H4GWm>D~bKZ@2U<N?*##KW6muTKOl2j z4U~KL9IU6FMVXlu*k|2tWk7otJiGs&2&~NAy-NVKkZEc-cD|P%5thiD9ER3jo(Qm$ zfK-8Wzw$gzbf*rM|L=C-fBJ%dHb9v<$IO+8t|1Qsb*?8Mf| z@|-Dvn5fm)S7PMmCU*_-18GZgBS?NfUjaI6W7?w`USJ{3_^~Ue{uAjtqCan3Bk9pA z>aXA>d~>qZoqdQJD^CbHL7ae?rp?Dr3^JfM5I!i6>wq^^FgE5p0KWtoQRFm1dPKba50xDgq z-Q5C-jqW96jL|dZ_=Ru00H&Ht1pLU*P-LNgfah|5&jws6)T-LR_EF{UK6K8Jv!!K? zYHdg2lBIS_p3*TZ-?V>Gj$jY=%v% zeoJFnATtD6(jK|@dwLW7GXyI9F?Cs&bs6zVTXUM>EAXhJnst}Hy%8l5=uVO3iPvwb z?G<^z@XmgKZ!6s$IMSCWATd+z*km_7G-Obxuq4yCi!%Qr`q$G=tx$kG6QOT$FHi2S zoKIuOBsB&ZmFQh3KnltEh0gwS3grNw7hfrQ|3!WMbFKcxg!xWgMBbK8&CYnl+jdRh zE$-<10PM8emH54Og|4pHW4TSd*_+7;F;8hxuE#FmQeT6yEJF)(d^1CoH=gd)HZNlq zD{ex1^R_r?XRSB17!m*@{Z;Q>9Y3=3b*!zvZGZp3W63+jPGW5Z3W3}sBC`&wX{e|% z4eIFrEc;mc5H8ZzM>G&a39l?`rW@*ii~l_4wFG(lq-mpOYDPW)$-crc{o>~H87XDU ziv{?RgN;Fadq_+d9j3875V@`}&iVpWc2Za9#u_Y;jMILCoUveI^dshiSGCA>mHSP- zr3hR?l|OSxl?HO>=ga|r%Faw;Tqi%Ps#SvTmM=`p6*!`B`$)QgXTvLB@-k7W%m;r3 zI*fjEwYegYBBd4FEi$=)UO_+w~DNXvZlvnh)XK!?}O_`@nOF#XrjoRE_FoZQ>^ z!6`m~67n4o0%#sdNT~Q3zUyC5Sol^>R^EQiT{eO=iUKx^-)ZCo1k+|u^)1vyWg_ke zsEeoVCv1SP1wdo2AC*P12&vph$~2ioSYk=jU3u)sk$BI_*nyZzuT1x?de9o63DPC` zrm}7_ZCupBr0JyNZr~6nT~oypQz##w2VEfET+A; z@)L$_znf`V<5!^i^?Vt^d~{7>xkHIk&#y%+sa%JLI{A-$h>0;JohW##RzZc4c>^7r z$*s|lDQ9!bZ=Ji$`E{Xm?|>t#54X2=nye1XAcJ~WG*uLQpg$k&yxg}-xuIIk77{VM zv64+Z$t3xcJ?HY>qta<}#njVcak$xNKI|;@Kyw{-hKwS+&Lz2PrvK*>{>_#A>v61nW`tcu7n z{p`HSsD)%8@EK_=S4uIJdv-Ih(v(w}G5-FK7741|BC!9+TVHHtypWd~p^L_p!Z`hy zHyjDO&70*^Dx(piO#;w-(|b`Q$)~63!M&>I{m*+)>G{)Du^93=%l)3{=IA9<4;+>WoANfdhpMPg`i3WK1gBBBxvlI<8*4o4F8{h? z43aao-Y5|~!;~FCzs}IGrtY-&DW=`SeG5aFp2UJ7^>f^s4BbN(9Uc_qmORrFC>z`W z-FG7IAu-7sxB zN)Qrbqvv>P?#rlOyn5r%G>}0qcW}zJJyR^7RQaWKR3(RgSxA-B( za7pD*ca#LlpY`M_E24_)JAOxYvRzwB?vyG;3y zZAUcHm^(p9EHCH+jI6I+#?RcT5fkQRTD1H$e|u`?jxPGFuoa4i7Czbdrq)uWv+19` zbc_%8$~<$j zWxVjD{020cJPCl9>4n*U%XJ@6OwezRJzf-5W0X~n4I3nrA6YPAUSG3Nd%g0tx?@$` z#q5+ktD3?gDO4LRfA=oZrTtRk6qy|OBU?#C>Go7@V{Ds)8-Ja^YRG?IE4~S~hrm*{SL!>>teQ(kTC&m)H&{=TX;Qf(t0N3Oih?BByyGVmedEryl6X{CcT-{ zsEcTGxUhfnb|z_4s4lAiZ28lb{1Cl_8N*X#)c~?$Cg#)Q?)KfaP*C z>5LYNb$JZE528afQsN?m%D!+Jc>P=9r$RY76(6l<2Ix^OS7ffW!hXlTt!T*6;0u}) z<{@_-E;jjW&Z32t{B3GPnLoXsK~;c_D)Tc^0sj;l#@U?QeoVFP82!kZoQUb@G>6Jrk+Iz3{5ANGrpslrMPBDe>0IPLk z9R2eduGX+GwU=Jc;TfXo8zdeE8F*?(N#~@-H3l--2G7VA~ujuAbXbiZ8ke(DdU+7qNeM4|du;0Nb2>B_}KE zP6&iT8|^xuRUwg*yz{>^*xK4Mpe-%I4fAe|uny0bh$Jy?Y4W%v9{&}b7qy&G^4-2B z2b-Qhg)OlCS+}4a)9K1Eo1VeNB3#tW&&vx%M%rHdZT27zgStQlgCMrOCxF8e30v2v zgTJYIxWW_`pY8IJLakJT{8v;UWGF~qz1lYwF9x!ZL3dYpu9hVneipg5i=)R@-J9~C zSD8)#+1GCByM6+HvcP&s&R`)lE=r)f zRX{kr>JDf8tZ}-4H<;U&)rq>PFmYzR@qVgN$BWP;Fc!)W38Cp+PrOPi7+^RH6fDlirdX%$7S{huiy$*5 z?H~I^xEBt)(2!;!Zo&5{kx3aJ^CL0loo4PQK}~jqYmfZgM(M5QVBr1&RqOD$ESc)qhNTeE4EIhU%bQi| zHOQLLKMOT4`xQJ}TC%VnJag5Xw^3q*lq5PhY8>tBI#mb5q?(u=BTvV=Eb3iup;a2X8%^lW8s4 zo_{>n&-*!^;Ja-GXyV>!eo4gSxADfs>!4%Q*#3XPL70kA)YJ5%lF`Wgd`0&^k~xpV zz8$*~cZVnTX9sSjQX3q{gL(qVlah=v|qAP-98L z8&$jaTYU_=t-MTDQE|v1+WjCJi5cAfNmoX=_ERkmitfnAG_GXKzpCzk*?@o0Pi&aPv@_4X59 zKeOlTqPTPuDm}o9QD0GbPPj^^=h0!f5WJ8D5^&i|f7W<-I^p<8%|30txwupw02u^> z%@qfUOm`*Nn|1`w(9d4UfncCrlLni3@yj25$Z9jQRT6J8hu&!#XX<`rl$K1bmzF%W z?2vAifn!?`6dClg&GtZms`BAV=1|JzZJL`Ip5kBM=W3Y1XBNHMDVIVm{wpD&@e51?jxfeEq8jln=@kh zIOdBWI1U@OB~Ic$=qM20ZjKpxqw&9$_rUWd%Ye#f9n&HzSO~zt<*SCUHv)p4n~iJtYm6PWrFg|fv<`02` z60gai#O>^}Pp<@E%1N*4X-*PR_)M3&b`ifEcM4cmE?YuveHidk)&wQ@AGZ-Ojj-RMhW471q^ z=ueCj;G0T0apqm941ClgiK%I}5=m5FD9aLxjlA*eX&wrEzcT-imZ66d3Ox2QpDx<2JAD%W=*9_S+a%0!R#A_2HiGZbL!&heI!1pwl745cs+9)=CU z<%n1KCVTUbyM-j{6@5}|P3ck$n!(EEV>uyH!au)%Z$>=AI>H^A_)rj(xUGag1PIX^ z7_6%XX7(BiScS39hH)O#@u=(h6^E)5$o(iR^xz~^aCzEh&VRA>+g;e4OZ}z!53MMM zz-*$_&%*#4K9{CfKKUlG2@S;07HWu0pqG)eEoU#VUJP$h9iUn|PVa&dPY-PkZMN_2 zDjX9Z;}~P;QNLAVdjnH}JL((yUg6gjIah#klH56isX|?_twBDRFAC(blc7*ae`R<{pBKQd zHfqDw(+ZHK@>xzpXv~hs$jwo`00-pzM&;_P;-sf?-KnWtG)o3z>wdmOO7;Y~(^CXVHbM^RUpEPtSb)|{F)BQYWOmUymTTBb@lPutsrRr1!6G`!U=r}c@ zI?dgSZc&*uXL8(}kjJl$1KWOR<_hAMYl<);Cpfz>CkY-4*Y;aaghL&b12^5W-fkUy zecV}P_{cB~@kx6Qw~ea2u){&b4(MsGjr1gk~JlN(UL}$cN-1si5|@ z->aOst%l!EJ!lQF zb6aY8uVCIetyv&PHhsUP+X4xxmT!3j_h?Kjz~a8Y8px#&mY&pf?_1`vJ9&{ms%MIDr*9CuBjC+# zcv&XwNp->0TPVm7?+P478KZIbaa+%|7HjGiE;``p0-gvfRS+0H-yk09uxq6&>9LY9 zLBnnH>v6C-Xs^2-%cTdg@g@EvDVI2UJ93V88u>B(M5+zY4l=IO-*SBU?zJ2A0-OG@btpjf4l%ah1UYdiCz|Gf`Zp% zAGUSWS~^(xIKvmdK32EYI5ArKeVlr44!78#@>Ac)&|x`YBtZMyA#C}Za{0Z+h^nN} zIx5qlDE7j2HD?P*HZOD0ei;3$%vO#?y)J3U*C& zQ&Qid3as(E3Er=5$L#sWVdogm%L-`7 zXXsNNo)nrw4gR*_uVA?C)RedA%g!^J6Qaw`-+T8@=LzI!t>Ud)yA7ja>oDVWXEU#_ z8YbD`LnW^Dpq&M=Y}KYA?D1RNg~}Lxjr`4qvG9)6v6*dE>0cUY%$}QuV?T+R5`H~j z`t(|!^j#*xw&8etF-325s&%ozt^Gi0J9jx}uRqvLGlS;xpHAW5CI4@%?z<4_1btdK zY_ALzpTAPhl_a3*kSM5Xk{7;jjhI`OQ@ShqveAXj!sOdx^Rp3QZi*E!LR1L&j1~bh zJwRD+6JlfO&8~vn5uG#|s4jW&a{q#<#xk!h8#C$Cr|ZS<0J?-l@^oN}6gK=2N8A@! z+QS%XxBb!h3^23&cA~C0{4;us$zgy6;^k5vV?;j>!0WTJtgG}V*wq7HJBKd(wwaLT zJG=8f;Z6v|x+b<`(K9sU2($u!f7Wix4?gvd!q8wdOs$R26B%dht?;i?1xj1j8ybxR zjj!3fMt$L_`Q8FUEY%t%zOojX$?2TfANj(2czd@I_o)67JUhesF5@POv!O~sj!7vzj27W(Dt0iz2=A$Wwz09}PkjndBBie1 zLkX9**YK6OjQ22aT2pP|mC}Y%;mDrzN(()Z0}8Xc<*m_%at#)3t2edu_X_rm5DNwcu&NEcG*W zxk5tg$mUT!8!%%bopJ_NJN38Xt(yg8Pu@)}sf`2>xZswO_8XiEGtMIqbAxpg9h=Z( z7$3oU1Nxd+@gae~X%aWp+u?g9#YfO&uxY6lj2deIq849lx2QjFjPS5tPh3aqu`?)L ze)~}ow*MuaP6;1bT*2ZV97~&3^sO|a^8syw?6U4(R+#eetRg<`?9k+&S0Kq8x<*+` z;i7x&hVBcPut^)x!cKmQm49bTE9nU_Gbp~mKsWY~1=9C<6K!&B2X~SO%8IzjdNjDd z_J}u2#j8rXk6k&hfA42sn+<7RJYn+Y8nFRhnV$uKlT)caw zIh4#y9AzDxfBI?ZxIUf$t(*UI8x|C#L{yRgBX*iKJymX z<}axP1$a9Q&DdCE!YANmvfT5F)-!{Fmks0TG(hSmV{|+SxJevWyo%c;EH1X=2ycC@ zzfq;}H4a|MnjnB)e2~Ue(6Dm<4EJUAGmH0%hm`7-N@A8=Mzi_s!mNrJI-QxmUT59X z8WK1zeU^O<7rFxZ*ZGs$rd;pf5D>Zg&DPGlYG%z9N5Cugi!hdhEcwY z53buyeJ<_qscS`RE}E3?T>L%EPVHRknM@^=x(WRZP+{^z%o=msMmj-nNanI=={Y!a z-pgVw4AGN~=-YR9Z1zLPCp>cqAE zP~O~}+LJYjf2{9+pCRGg@q!KgZr((At{|=qxpF|;dFGhhsTiaY_APU7kJ<|nn$u8u z%=Mm}Ow!8}`qkF|?c!WLTyCUkIS3v6D)+zaQF{gf5pB=*p8r^g>f1llpmg7H4|l1{ zQQFJ=RAvO6$yW5W>R6BfOW{(ugv}p2RtwMCe_CKMV@%ly3UMC*khIPV5L&`A(_?R$ zgY7Gv3HaBk9a=V!dY2ecvBP;@JM1#@Q{?p=6iUy^2_ihYK?d_jmk zd>fAFJv;MSqpw9c1px+jo@+&@7tbKjNV>{FrzBD>^>DGA+ekqX@Wr=-Gl&QE>9XK7504vEN3Z+YL`*QSJU%M{tRXAFC6N z{-aOYrBw*$@aa|s7_1OSr=ax#@dZ#U>aB`Zgg2JIobn-SnSFE7_hl?9-L+V-xwxfo z&-gPE*&h{NlfEO4uNY?Fn1NZ1Cb0$1qQ0}jy~x9yn+L3^^p|Y&9NPK%71BcU+wWKd z2}bxI(P2#TZ=f+0dEXkX0IhXEd+I{9!pI*N2lwrIP=Id%285%1;v4t-q~9)Qg7YQ6 zeoXVF_79slCML7rO61iKtxSTHTd-1V(Einz5{0}xd8~$!bHsy^@Qy%7Oh0L6@#8Ax zElr1<6mp(?#O7E*jniw7qD*mOr_x1yE;=0KbuLAXH7MTa&5s|eR(L9p*Fz^kgsQ_r zo|$zNx45356&Y1J|a{55)K=F_rBOw=v!~S-K&x(;~wv z{7dR@7S1Gw z$cn*fTe!z&Y#mL(qCOapv`zg5cyU9_LazN7J2LYNs=xNlRZXGAf(h}%BC%Q zg@FEwVnFNTm%6i+=rAVcLX#)dW7`0L;7*aHh!7gxYnbDGLQ2b_5)0{SXrL&2~uig@vcAWb-er9*gXp z3vwXZG*%CXyv2CZ_@g`5e>|}iz zukUTC)HmE?%oQk}aD3J7mBw!ssm*3)U)?P#Y@PUa)4Bav;fmKW_-v0QWE<9E>$e7a zI!8?8)MWmwt}V(UEv_!e?fE1me}G1CGfAZSG9$L<|t=mo(UW1jDJ%= zMut%d6G_u=fgRQno^=AfbUL0ZvFrul9lfK%Jgfrq(*w^~Los^Vo8u`NT_!RgD_vft z0aq#niHZsW=#jnqa$5E0i51{+E~3}$CFbr2i}q$kUbZOQA(TfLLMUJIQ%wKDIcS>wuzvpr)`>y?-YD@8#XtANl%c zKR3cUzHyB!yxW;)>weNKKqBq%=9433@p@qzcY{8MoZStY_$8j*kIEwHMVO}lqI}qR zJc*RIB)!DWgR|dvr1#H?RDDMG%wkgy=_ohVG|@BMLw%b2M(Lg0%}mMJ>}9_*N-M)z zW`85lm5F?0<$Wn|r5R_rO#qqRqU*GzfBnlQn+})JVg)dNSa>JLZTto*MTs#XpKRnI z^ZQ0zcwa*FAEzcZ1$m85(cGUtE#yy=mv4!hF?_1#1$ehVtvEgG6Y9@A^!=<(EN$-t zjMzBFs7T@ztr*;-zmA^1!b+@loqowv9!8mdH z&;9N74W}84I-e%Ud#jj&)z<-GPZ{Hfk<}T9Ot&3xYhDlU`Gq`dzA!uJjLPNIMnFB# z$>_&=H@+hJDwna4xE*>-?rqo1%z^8qK+a_Yt%~yMS_7^R=+?RY!k;~Ba|lSPv)4*% zzR%pIthY$qdc9DXaCP;D*3?l93|^JK!)<|D7jpmW-ZdpdHCIQ;kG`>GsROVp(lM2% zAUUv-Lr{asuBp(ptgz!&nb=3$$7C_Bs!s=@^PksnE=2)z4D7=2X>RE}3ygzY?0y|i zap;nPcGAgNGOpU_LQT$ypb!~&oN!yEc6M=5OqF^v2%mn+nnYhLh@vjJ_U#|Fb*vp8 zHj@6#6IzhcSV^Ig79-`xlGHR8yI0;k0P@F7g!?l7T+j~fy}9yktFZm)$iISC|DSvw z%s~Y@&DHlMrII?nEewv~!CY(HgNJ-zqh*6p2ac9E22Govgqi*<;955`d$gXr1FVKu zUq{^5`rUGr716{J4oqq)IidejNM5xAM!%Kjd>LY!%&ZhY(qOH@mhezEq?}(p^fN(9 zhEl-sS;rJ$rm%ZONl{HrG8ud!f}3R*_}S`cpU6zypEB@x%))VL$Z37q%MRRAbWgs< z%6StADyLrh-FF9K8xb1nrhEH4&-&|jzlPWfXI}oxcaWJnMts5wfXX-TY~QRIv*R&S zSB$S6en_kmZ;nN>KE(`zH5Bn~OO^V{so2#kQdHa_|8yXX7tFH|i%gHQsx*q zgn|rouJi36lWyM$ctzX%>{xk+YCWK+HLX=DfWT!KpPyXD9sJREX6`QSWKlEC_DHnO z{&1KZ?%I?_{*3|6Hg(2((>EU{y|-*dwG8oRaw0UXtsF*tD!TS$$9NH@Sb52z^rR|< zari;2V9J`+J74Q__&m3CP9r+;TZF~*4~Vzn^f)^mHtqvbajI53Ea^72=7zl7<;<-e zd{9BZs6A=j7&IZ&6M3sTBcy#eFneX~AM#hRNazVCR^ie?R(kc(;L;t9IgS0(f6L|n z*rsKveT=%ozbN1S4V_=a(C)6i(Do)IU2`|AqdrG9$Wo!PJ{=$A?^@4)H+vashDTLb z^YVk%3sdc{{-F+AwVJ!Ky3k&4+xwu`NIv}gc*7?d^X^&gIDKxaEvN$Egt!fBVEt{H z?vtTB61pqE{KhMC&f`e{?O29;Lnko+#f=~N=cd{;7XO@3w@;V*dG2{?CR`HO^+W{Y4c|Y>HZ# zkx1IMXfjQ=*y`^7pgku*V-(hzdL!VEwSgVbJ+F;r_(Hc7%JQO++-`f~PK|frzNn)7 z>><}gwg>lu#7p}741Nn!DoEzP_;>~G09XvWzGQL3v*cc+dh<*Xfl#)z-BuVQ+lDG3 zr##w1@U>eacK{BDljN4l126d4%weLROiFVUvOcp%@KubovyFABghpj$DOaelW_o31 z=wL0|y>D9R)@E2QJL_@cEVf?gqo3N+C6@ZhJGCC=FuRvupJ0NTd@j;wu%uH`SFDM# zZBh*+7^=7XIFlf;JTJG%P@klQ!fxI|&I1Os?vsn{4Ckegf-Ir@Efl zD6A>Rh&h|P&&Ve}s?qRE=70v*2bkh^gNR3bHxtuSY@ofsL#Q_i?uF)6u4JQ2Y1HJu z1#ju$RbnMnlV=%mPXC6v!^cIYnQ{neZnQp^6k+{uRtP8t?<`>ryD_6b z3>+TQa1~iuZql6-tW#g5B-6BiX#s18!qsugg8jb&N-(wLUxGlJaxW-on<;z&FLo;_ zUuL(lqr)eC$lJS;%mMh05mQnWf5`m&!leTNV;?;x8wXL&+Io52ssaf(&(!bhdQQ9V zkRMFweIGV5TXiX95#i6Y7G%YOfWulYo7uo7QQz{u&!5{6pIr5lGUnzs(5!>zgHEb# z{f+DE=5b#XJ*v|r>S7Y@TFO);uE@W9p`YT82!m^V;KiZlku7lQjN| z(tX+SICVm%QtcQc3#|2n z#ar`qV&6!Jir$|&8_bt(`fyq*IaCfw@1@d$MFR^< z7itIdcT0MS>6gsJdySUY@)8BD$K3VCqxsvt9O*=GSV&)FWj=ZUxQR z^1Qh^$Dw_c;gwX2?^L}Bw~EwSUnh9^+X$_0w`^DKVtXK{uqmE(;T3t{Jkjl(FQU; zXh!7&{HQW_q~22mL4@!lK194u?{&O(9^=2PkpImL|Lw)|SZ9P=nZ>9Rk0**fNb!xg z^>I+d1OjnA#)MT^psnbyRYmjoQx-Ll56inD@Zds#^_>(9M{uJ^k5u~L>d)B8W}Bc+ z^IkLJa2EIyik$hyoczV$jk}$`sn%Wr`i+tF>s6gNwhUEM=b}Ft8d|>W7l^_8E|ks* zt{Va7(ke3sV-G$a;!A~L)q~s6{VRM=D=WZ+Yv>8U6RpOG>hr?i1v!V;fZz7NwWTRn zs3aJ0CS08rlmeIdR@MaI*HE~ioh1u(Jl2q-3~Llu%;2D^FlwY>&4J-4B`{64?%tc zvMV_Std>DN^qjKjl{59;FL{iaaxHFHhKia>p}I`Xt#(O3LqHAhlqbXT~qmmRR7r6rsA!*kI?-%&7}e32_Y-;`#UP;fw3El z`)Ws!aPHT3=2d0kx6dUBjW(C@8rdVTN(FkuR^3`sI!on~`s=KIHk?%nWi1uq_7)3k zvL33X*HF)!O~mVk0Oo0o#&YB`O;|7`YX*b6tkX!!o%3PCU79ChGb4*^$ z+_IOIanRJbpmfa0)Vj+4UN5g(Eefc3SOb@C`GCNBRF8D(7vFaDgEH6J&#E1|o*UZR zb2iNy^F2YYj7NL>&b)RWq43qy%_dqGfvH|GJ*n1}jBOv=Yc;FePAOlC$qnTPaRV1O zsf9moFd!Hi7`J8>p>*T+N%Ye{R8?)=!@$I!Nw~if+Lrn^o;o}h%G-FFmlUG0M#&_( zF7C8X3z1l&G|oDz)99K<4I6m56w0>x*Zwt*qy6c?zbJ--Um31mOOby<A$8nJv8t)4)MB&MB6S|aaujM`Jjy@n#UDJAgy660l4ki>WOf z&L(Z3s7%+W%~@-BpOzRu*czy%99NyHW2%NS=)olA)SUR52Mz(i`{eyBXz|Z(*hxCF zfCV?T^&rm{jcIFh6K-kx_&7>>(B&vTz0?0iy;}Rx$IU!Ld zLZC?Ntod%NCPC4WKTlaiMiD~pKx&|t!AC;-PBvaNY(5By@({G2`Y_prd@)x_e!Eo| z-?(LI>k4i@LI1vJZ~NVNw#Y-|483GSe03{NEb8>}neLk&O={nH!D(eajl@-LOlAo7 znH)R(Gh`A$H0(i!f+$%}oQ(17M6RiZn{=G$Az+EotN045t(kA$>&8(n_cG8T!V!9S zt&&Qf?0|*>N$3dn`N$PRc+tAs)$_l$Cd|Fl@5c@fDEBq;`$_D-V$N7lABb85_aS{;{l5cU{cmD_so_(y|_skhmDQG2I4qCh)fW)%7lODP)1ut_#H_(}Jo)UuZUFk`})u zL)h%z>l>6WkG;VyLx4CrVfT-VunSk?1uQ96tE2oHHd1y<5~32KrBVLO_3j>P&7||G zPJ1zgNv;bsOSiiJT7&uphDV{SHppmqu>B`!nG3=n+W?(204>3Ly6TV)mIBgtYBx4W zVnfh2v4A_f&(`{%4H;dsT2S5V$qEXesR+}VxOQ#){ZiBC9!sMQ_|@;;(}QU?4-7}X zwb983-I?q zA6~@F11HB~0QytKST8a~c_(b_ACP*T+9&Q+6DKzDcMvr0-#q6pklN)|;E>gDZg1u2WmfO>8;e^V;kvTqwYU9tSDwKF%^*)dp;7S<|TXhl;;FDlJ z@GmX9P=wO&QN14ASP=ks6^$_Qe_{GXGQY&_{xfgOmgqhS2?=*|^4IPP$IHP_pG`PP zE5{<96vJ0+nJs$4jFnv(FTCT{cl3>-|A?WhFLu{uaw@o^FeN?UlCe*bE^sZ&qJ9u( zU~pwOYBzNM!7EqFE;U{I|yGe?zePD4Qdg2chgUr z@^!=(qpbu@0<=r;cQAE#Va$3RbMPYkYv$zXtje9Z7<13QOexo=hSqKO=J*tbJW?R( zpRp!Q4uQ#%602VFr^4{ICQX05SAFpG3!^`6p>HXtq_b~J<_>r#+;VYmw}wm%Mw_S^(>7->3Yu~`cBveB1~in*4Q@9#%i#@pgKru zhWbKn!vb_=oGe4CIL-1U3zUioRm$%XRi`X}q18UguQ8;HfzNfEAMt$yIdR9<;eEp* z=9&ehEoS{isItp;R<@2}(v?-LtgX2!Ou_5VtWsDK^;r!0H=8RLJ6J9(y;ko7_fp9@flCwsv-x3$7_7zp$?plPoFy11y&8Z9xf%qxTC63LJrDE+Jg9 z@qBdtM~3nS8V)LV0Q`QJHazyT-g}wjK^{O{jTOUtYgRCnO?SO46$_A={Iu#$MC?`d z*p`YeT1ND`6=RHioM?BL9mI612Ru#&r-m#AcelPztPoEUDj7Jb9|#TLStb03N8lmT zz8ZBAM_KY$S2~=PovUYi)Dl8YKEi5!SQgI>LRtiDY^XfkN_X{Z^m!AZH^R5@9ysbn z*|gZ-!oxTTCr49q*Gek2zt+T(cS7K}5#C{y^m_1lYX!kFVAIQfnjU$TI@>{;unUXG zFVZLl%xI?HLcz@npk+?3?d-SmC6}muXONWQKznvjk zCX4LphrtChTCp&1UUT>T7&`F+-USR~>DUPSHiU+k;G-!H8ZFTagE_zbhCZUJ)FQ(B zJMu{79z_>kJFALl1#LwciUK~cd3~dUPVEE0m?y%w*PRm;W$#YOi95&OSl@>@S4N)v zlu&v6;6t0Ef`p$4&~S|3;t`>%G`=abxC7hE9g4qG>-yr@2ZLg{&Y-lk26!HFEoxJ!k&R1&4#>VV~Noe0fJ zB9M?`7H8xfZ=_Ig_2zC(Ds~cqcTUB!f=%*NWVSv#p}V7<$M~6S%>=xQCvS4FsXYd* z(QzSCoL%|H=2`;>_Uyqo=cQ&^Id!+~<4Wa&A{rn2;L4#h{zQep-m6zIEg4foX*QKV z;5lT0br;yodT{ur?b)0C3EwjX@SQI3;lksy1tGDqA+nNI!<>PC3!uZ&!VhcYvN33z z{}TJg{Uu``n-ae4qXnz}a{qz1zQ?|K@vd$y3MM+XSXsfv<1Oydcn7zdp89FBvbNWf z7quHWE7&(+vA~+Uux8E9)}Wz()J*>R;7Lj$YP*{i)cC+n}DOS!s+52QT%gp^@ zih!k?_GskMle(_LA2*2o!&g8U+IyK#N0PqEDc-pZ0U9#0t^sCVXK#N4KI8Z@cdju^ z^A*hh<-0ft(bkaeC(%>d2#Px)2njgfOZVdC#4`;|Pqkls$`$UCe|$BYY~ji8|I2Gh zjtfx_Hm{BoWuuZ8ZjY%QBCktIW=0)F9SRUPDV4;&$e(c+R5A<^s!B5E9Te9k8=u9t z!lA{;dQXOL49EA>e^XkyzBW7CY^@!Z=oIIwqtjLAlczZ30q1XtML2=#oVF)OQ}WiD z20d?}KVL2?UWg8J-++KvfC^gtP8$VtKncZ4gw|LkQ$HyDwn0SvNCU$AHb_(>a`OZ5 z31ImhnV9u)$)kX>pT^9v@F-uyT_y|Gm6uhANs3nLq&1nM?AxEns@zq-p}UI|Q>#tS zyP9+3vG?jQi-du6Kf+zh-Mm>1!c^%_rQfwZSU*|vaUPa%a*fb(A5tkJN3)o_F4!H6 z1{WS2 z*G^67S=Z7LjreC{y=aEY>DT-dDlz4p?8%>#(#I`dzX+`7@9JlUD2%@j5KXL_x6vzd z6UMx%#Y0byi~1Q$ zJPiJZv#GLgYj!F^&H_UeWzd%hT-~X{yQ-&dZb}SgZ#4`$+S^;=!>vVY8AmyJYxsy-aQp1sPm2|BWbm17{Uj&PSJf8#zFW8G;iM5% zpsVYG6MtvnbkCyVW(dLuYX+D<>3y%YS%9r3af*z|v>-xQm;@bLpF0q|dkH)t5he_v zSOiAL^pdLti=k^aV1@IOQ^8KdWb2T`o6_-I?o>guJQp-`&L;bDd*D{xW?^-zGqh`e zjLve4lBA>i@XuK}*Ylx`&8!Ui;-JCF>v8^hNljpd_P*hwYgjy1M>0?pFEx zU933q!Kl50koyJWyYiLgM)m@m6odd*YaK`BlO-Q!D|`BlL65irXVnpnz^y#W$YA*{ zXXZTpq|ciLn@3?jcHnbdEBTzYjztU9LcydPsIv+wTb`{Ron!MD6Ordboj-*Jm(B-- z>NDTJnO9NeM!)zbCEtHV?EY3cBMiZ@2el**@w;tT(MY5Qftt?6;BT{^E&z6|CGfk%erC3i^FK-Z8Q@OR+T zSp(d_3#baGB$a*LX*F4xKSLBiWPKQY@IzUazh_E zVO=n7+%p>Muu8Wvfnn876V#_i+M_j&ftR;he7hXxuocs_Ic+Bz939=Tu&_RIi3!cd z$Ch!tP%3f<9BD)uT{=>?e1Q2XS}C2@c>-E;T-iYPmJ+Hcv7pR2`g(PYg_;r%|Au{I zEW8G3VE0X>`+w+q@2@7GE?zq!1e9)}NmWGYp-6906jVS!I-w&)AXI5m11c&~lqwyO z-g}22C6Le*q=lxGAcPhm5CY^~exI_=bIy8yx!3#wv-UmvnrnZ?S?qI%6~N_;9i|zM zRWsjSX`Q#Q0nM!3G@0owvf1#PwG`uGn<1LNCLSKmgatM8L~4ZyL|2Qpsrq~9RxE#A zEw9*OwZ!6r%qwhKUp#@kewk~PbzY@H6cxp%ETi=9Y~``{)yI(%ZfWW>-*VC?;_z#=iv^Uk4|tLBmf+bB}Y zJssgR{gcXD*x5=l&`dvxTzJ?Zn=J3bGA#C$_4d_vp$LZ#MWAu#@@rKY$V6PkGc+GB zuP}_NN#$BTUL%?*^}*_6a3$~tq90m|oo(_fc^mZMvEuX-!`r!1Q=++qw;O#gi)=z4 zLg3dYl5~A*1{YnRuiw;QjlV9_iM&*-9gw zwaM35i^Oj?W8{XJ(j7~`G>TYOJo)*!xx|JiDkyF?VuHyEmWH3~g`e?sJ?*Og!=&xf z$jOGzyR%)2;F;VE1mufaG95}g_MdB>QSr8YduceI%2w3md2=v1G+pA9qsYq88H;@dpUz`%Klp~z#3oG?Lp4zvA!kc z4)<(*JT;qHR;K1Iox(?+O zT3&RPMP#%sWSU?0@g=6OR`aIx9sl^<4v+WuH%ny94*4yNLB#$DdxSoP!xMdP`gmW7 zE?PYN*;uhQjXM;s(u+qP3hz|ypDX1+R`!$sisq@ES4UHasFaRhD)V^n*pPzVcJ^~Q z97CklvMvr)J-_jn5^juX4rErRYp&E5 zs9Kq%q@e3OgSA=&*Qve0>3Is&BUCkj&hQAc1FW8lSaKyM%%Spu(!|0$E} zZ74~9tRf$vVH?y76^_9Lema&37X4w1QWIi)|3&BHEV)US=76F^}<|FM{4 zf%Vm7@Afmj&R)ktdDpcsuzDbBBe_KPY<1dz7VFe7;nAqa%|O#8J?lfzl&~vvHpZH~ zZt1HQNf#C{YA+5!lu98Ga-Jy@DVu45fgwYLS)-BZboy-52aPx}|DUq-3fxD>`&^FS zw=MU!b6^TvibWRziEKk69f)D2TkpxN4P^7x#ll#~W~R);D&HdG`(>fVP!Hyz25Q{M zJLg5?H=6x60f5g_@$F%!nw5Otb8F9@kq3#1N4TKy>?2(K>{*a8U=bo+B_k11OaY81 zovPBLapt)5RmqkN>Ag!%9oHQLE)YY&F?3EKurV3soM0%`f&m6%NUHIUdOOl zN=xB9Tk-O1#=03%?NDW*w1(@)+8);KUO@Ym-#i~(Cyn0)FwR;?*j3QuHLmNN+YrdL z+>1b>5bd;9r}b4-(=$`uP<^4Q^vi*>NeNdcsKvrb^WL+2Qk zO;t>j3NA`bc@`eJ&QaG+Q_~@{1@vFMm^u$(_xiU4oiNG+1+%@>(JVtbIrS&Xp zB9LL^8nmKjLV7+EbNVFCJy(=G*f>Lz%jUNOH$q4DLv8VCp!4*NH28&MBJr^F15d+n znA^C4C&r=taJuVlk$DjP>C>jL3HrAG@MO~Ox63?BQeTQFio1w1bE5B(b;$1F( zn>f%h@AAz(5Nh(rj;%1iVmoRpH-vj}C0{kjfNGn*z zPe5^qjS?(7@U)~>muVrCR;MO-W0jr35~vR}S8k)~V0}W>tB(v@*Wfd-UMfOox(6Gq zf6@!kAw4!NxFHuIBFUN%D-C!te_C1SfA#bRyHxejk3M>u=LW$1Z+DdE=ycdU#iyl_ z^Rb71QPxn?MnQJFI{O8-gn8CyT&cCGC&00YZ%8xZ&%AouYJ553M}&0lHBuDN1KBt_ zxRy?sNzpJg^-X^|x##3d%Y5NJJY?^bGYZ}72zQ)`P{49?d$2#-TjeI0o~NmtpsCv zskKM9TDs~n8D80W_y}Nk8~%10D*V{A{BwtUR2_{9&tuCxo$lfdTlHi-^--V&S0XAOEKEI_<& ze`Ru%H(1xYcycs5zoozRo7u*9q0jHy{JvE_UV9L{+SfVm^xUu)Am|(3rD219A=Ih2 z%kjE~VD5$mHkL%K@|wiqLR}{S0oL_?Oq+kktJ1ahlQT`vZlmAMbU+D+w@#F}joa2&gPFHQ}PxDhpa@Z1P z#kJzHg;uy#{ZIF#r4)@Tty_#nvVsP;95dWHjT$1YkWKG;P?+GH;3`{OTJFXtAe7L( zedRtASS0>c^(3SAZ#(mGszbQ&XevT}1`S6&aXQ^zZL($|$Y zf$-p}*2#)@pyq2!e&;aOn!MjXQyV;JBoRHcdiIy;#s*lqO-8e^DfSix5I{;G=tj_` z9Y8-)-)IhqC8^>+!dygL=AqBE-f=sl?;|=2LPosX&w@8l($l<)H4fCrE2_|&dnB3g zU(x8V_Ps}2%SQ1aviGAaSHjk5Dec1k0<=}DbB$tWWR{xnY{An}oHGQ-|zouks6JS~KZ5okbD9wWo)giB;+pFS!v^1)fy&%?s21FEW_G&*T+8@V*7)Rk<)^%Ed_g?vYOW?@5l;=N0ti5u;$aCfdcmuNN36>=#=*BVjwc&ljvp+%CgDRNo&;P2M>d2>+5#<*{>ZZX?LX+#-{m z`kdZX1~c3#m%xg24T_w9uXwdJVrl@3Y3nvP>ns=qnB6qgOSzjhCz`-j7buh}4JdL7 zs5pVm9gO-ike`7&nOWeEx1NvzBjY2_W89UIvU?8@PeNyS_wJBA(G`BTpVAtcZlGe6 zyehvxF^^uZ%^##mg=97DJjd#!BO}x0G`YCHlU79RJ=K#M#En&0(%@Sj@Fc8-hyKPv z_QH8cXORN#u=vmKfA+|Jo+{73)eQMxr0OaIK=h~Uiy0a3n_C6~x(3k-|4$gx|0(vw zKUS}9tFi3-wb?myJ%|5COb+D*Nh5rnjMh6#%n`{sOV&%B*)$c~fs7?nPEL4=zs&V6 z1R4`-p^`>luSDymSROa-p)Hnby=x8bz5Z5N+qrHPqVTGx)6 ziRbH3t6k&1y6(Wa#4R%5E#8)E*=>m44BlU3G?e|afWL&C|0K=9!oWeZLe;xH>zS>U zc5(oeL0Cn4m&dHibmaKz2s+6T^$b-8mS-`KM>j2T268Wr@!K1}43=8? z1$OyjsVOyl6X6rN~3$rK4wdufzH#eQ*;Ly2gKKdJg z4qk}i;UxD|ELGdRqnBP4;_08vq_&e?P4{o7r}D^0;jIgKo<-p+7-bjpL*h>I^|b_t zsOjpyRW{B~Bsaphax#0V=E9yRU!diNDPIOG3Ux$|W;2rw{-A2J6}QpEbe!9NW`U8O z^?WW@ky6mIb7eJtPc5996dkeA0g1aYekuYcwac4?1_ZE~f93 z3HoltXa1WlAqdlAtwrLTr*P;~yc{Ii`-tctMC|nj>6%RtI`aZ1+JvH+b@?Q;wPR=u zg{S!D0^_h@h`CtZ)kD@|du3#~-|8Lk0o6ov0ml!b$0J6%q{5+43$~w9P)>|9Z4i1{ zw7+196=_Zr-0y!=?rqF=cz5sJy+B&Q@(9jD3&YRQCSTl$*&6Bc>4A*X4bUVeD-E z5h_SWsEMiH%Wd0~BEZ$Ga;bgOevKCgwI++nTk19N!lN>IWyLx+atX?2` zyEI(&jTyp$Q#ZpoX!go#^{7r*ZmhoMbQbM&Y;$e`F2L|ondSNRnn>ftEBQV@<#BoYko2jX_VZIG>+q*QOIlKw zL1gykDnn)_B2mWc|3;Yqm6oHc_|iCd#dZQu1__^W>TU^tzL8AD)y2K&^_BeAtA%a# za$eSm4R~+@W{d?a&J9&%)>&0Talz^b(7q+&i4Uo^C}+|$;Op4Dlx>U1ru9M%vcT#< z8_^uNnPOBcu$tnY3M>Fri~qFKPhj(_?HV?d z4F|EWB^&@LTPG+!;+t4?wIpoqYR|iO8feiF%>K{Ph4JWlrfV1Q&>!$*kiGvt>M8Hi zo$^!xZZQop1GS8edJ#=fX=C*jNxaEO#HL!j` zJ10Xz8_##yb78DsiPk^sD@11Q`kZRbsWw&U-C7Fuacw;*6=0$Qv{XKs9HXPs5lft4jGtcD6t{}|MH(Y6z za-&j9-0$99VCtQ})mqassm7U5StFAGtC&1HZuyq#OSkUM!jUWozu4yI{`IpCvU2hr zb>UnkKL>L23KQVCG(M^0k_IMVs52w9IVYdHY@m<3=K5meszxPC+S28^ii#{B7|StK zRek>?Yig%GOg&_3M+LIqKC~}Aiow%%Dx5_CZMnRqYU^hL{E(bE%JTew0Vh@~n@_^F z^FnHPaq-#_^{HOj5Na$NGnc4#vyHuaz3*nekXc&;CNxrLUvSBgFQGi!6cr+#{S zRqyQc4n*F=5`v{FV25Nj5`!M@23R8ra8GhALDuFBhKU4hjh@YQNhv!-XD$tv7= zTBxT6qj991zC0tpiNKK;&m;`TzBGeh>gtUqaZOcSj2Ibs{Bj21(zW4Bsujy~Qj#r97Hd??OKMn{n>YM1Os+tR6Ij=(xM+drWI?t;?EMQv zeFsm*XAio|7fIMW2~wcvRC|Z)?b$3s% z9aadJ4QQ}Tu5N^zl?Kny%U%LMdQG3nROkbm!_AEd1i1Hj#eGEEOM_9bTGK?hS**k> zYIKg;`)Sc%Mh4HK5*x$R76P~5xOH)&)&uZk1Vg6}WqWGPJq*h*4V%pVV0pprKENN3`q>y1X zGbjtpHEJ@VXRW1PqZjbagEA+QxC~S~gl1hke8!pk6{b{o)xQU-a~Gq@i6?%Kiag-r zsvT}Tt;tT5TOx%)pK0}Nq9^7x3+P_-NzWv$_|fWmyTA7U;!4lq5ycyO>gRvD%H;yv zYdSmvCR0l(buY^=OjD3HCx*4t3-wlht8Q+wa5@Vfy`;tIn{5voVV+#~8=8sF&%_rY zxfSqlM^{`Ps|xJMZc0D@otrD6KkXyK#V}QS;tZ!Ddv65@RcILNqy_(sdrP(|Sq9b= zHdZ39HEUyUJ7sd^Rj)NGO#2D(=<~kSJ=1k`zrqDL@pw1lW5VVw@8)7OnJqdS(U77A zXMRy=ji)EKTrczC-(|0(4C2ayQHnvKqnp9mHbIosqwpXKPG6>qd0yev$(j!a_LBK2 zNcmS}`2V<;{|$}bb$Jj$J3KWKRv9ubPjRN%0emge3$5f%&lEvDQL&b=YH@d+t8=za zIbpe=$z)I>2abz)a#s-XVP#PDq*ocedwftOe1T?p+dcWHbF;-~Yr`?>`O1=2TF#Ye z;}L_qMWojmjwfR}iH6CMKr3jA?kcDs%?V&Qv?m!0hay_IsD30h2zsG*+7s)NcLvTd zFWaljY5HR^lP{kDf-GGZ#JhEpxuHy-==wmGJGQiRF%%k9*GoL+`Y`1jRYl`0T5Qsx zUkrNlt^naD9&MkpPc^;imk?XGI%#Y!l0k53(|I9T=7jl$`AQT2d8=+RpTRKPG;ri5 z&HXM=)a+W}?42?0GQvx>YGI6^lWOrHftMUc}sPyvO}$M`;holy!5k}0lZt0 z7nrH|QW=7+wo6?ML-hXV(e++K(?s6vd#)6_;EW!0{V1G*1q7CZ5Xq)@U)YE{U#YVD`a zn-9JKLnz;CSe|kD?VQTZdbvAjADJa?#eT|EM zz4Uuq3ib%yfUyWSTLj)KJE=FAc-j72ippyXKV#S!-cuW9eVMxOeA+ahp)ihSX*(F4 z*3in4^g!6MA`KB;=zka}OY&2GKiBNJZ#aRH@D9;!DLu<`sSB^9Ta;kfzUMyqKy}0Q z*MKO4ir^0X^{AMkcq5`PZ@{>M(R!Z?MddO`fBcY4hjdkRH_pQ?>>IBJg#T{al-i!` zlv7>2Ql{*UO_C+5pLB(NQK5X+Yy0ujvE6uYv(&|2uU!WW!#=_DxtbG%16aQay#UqA zv6yeYX?*LGLMVnf(u@@{7}9{OKXcnE)^`Xu7Z6n&^6$F&IwdkH+(uQId+l&E3*O56 z?X*ZWW^W8E)EXJ2Tr(RWi4=PMC#;z;91@!f??g@5>5g{k#>n=x&xp zP144J^5v76$<{e#s`M&;ORFz@!`1qOiHFSXodw1qrsi8&ZXHAZ@XZ|w^qn|A%jFOxX zFmYe7o53Th*G)#AjqgORyp8#Cnal2K5=+_6w)2|Rxc#ojVD5aGttHj8F zhY{?ObW8ISwJVC&Fqm+D{<0J11D&siloFKJ))qEw=vHc9@~Q^Eb?I4;+DrY2&mrHM zs6CnKP8QmOtmxK)Fq{m%44X;T=|5=GB~c*3o>WCJla!-MnF$rsEG6Ig7vuA`8ZtsR z_|t_h>*!RXW##v*y-n`h-+Z_U9@KkOX{fK?errJ}J&jAiG?7DAs@tXa0(t^EzONX% zR#N(8*tlpTQ|*YPzGGn%S`^LTt5cTUvZ*z{TvRQzDzwYXzJ2bmW@h^xVSVifQpI-C)gGtDq%cIPIgW?`=BjH(t* zNiD@-KTaaP*{Jh~(Nip(!b5?Qd~p?DR0Uy96JZXuTKx;8FH1kz!}l;BV%10`ZC`y< z-S}mtm7cPhPGTlHxfs&ZdH2JeLfQhK*L}c;e6zTX+CY&cgMzDK9AKHaKSoU%T^-VRz5rso(=Oa3(bi9 zX)+{B@dVY@x2&c*T2ld5RPnFn3w9aU9ln-O4I_WhiDo#~{jxXy_%z^z4!f&1*@M?3 zi8pfR5Xui4&b)-;G>qxjnF~DYQvKCn78~3R%E~F@?I^k8{P5ihb?Y|;v;L*?g>q$4 z8Y$z+`5^M5rQmEydAF%RCWZ=-n<{gP@ZKtKfsI+>6oR3 zu3A-+-kR z&Egt-Sq7E*5Aql$(3xJ1==89 zLWji_w6lLtFPaRzzZ-?J8yDk%!QaDp7|;2uUdqO-q}*-<{-99|%JFqLespfZ14_GK z#sJ$XrI`$xja*R{(5lOIE>72w-I^{FFRt-y*&-6=Jp;94=h+tUDOAzuR?SvoiSJWq z%0ztEFw5~%kbDU+1dJia%OR#no2y(1Cc%G!leSM8jifx3Bh=XtK*?*^7!nP zAVlcPim*aGZ>IE6MU*oP%~&As#m9xK4)yPM6#W98sd21C$-E7C(P*tpKffR|aXXG? zp_EHM6qc#JQ*}h#QC)I-+sEkK(7fDUSw+9Gc#vPni%UCe^(gK+Z0ay$>74DbNiI{T zAN=<~%|EBN-IjP{BYWrXGDz?Pdqcn!Ydk5yswQFYEo<3~`n~HpXV=LZ*362$D}iat zb_>jeu(W+dCi6-NKMthG7x;LXRsvq0)RA~)>CWBk1_BZkfcZ@d8i{JNTJjEjHYd^( ztR9+rw;IT@RK3;@KA%xD;U~5_t9LQP=~^cf^Q0G4rTGiCo<*pi$pmVCevkH#dejQOnrr)r#Z(;hlnR zPC^UWfF3qxwgKfyZ6y$37_*vJym93O{4Q!$_J-SrRLMt_p9;Tq)XGP_)Q~3NFpvoS zt^auQh>lO=B13(LJ3q#keirUknRaJshPOl3%N6U`cU6A?0jLIir}3OwKy5`9-WgrZ z|5Sq}(2p^sNCfL&%!SLST>XY82loWOXc$wyN3m0XGOT{v=K+7koi} zj?iA)Ay06}?N^1Ir;e)c2L-B8hH;BQ>I39oGSAg)!Mj&xS{ffYg`FS!hjHe}g^nDn zWb>F2z zYCV1G8PKySAnVKP@Rmn#S@&jebEke@EGqKo66yvzweY&R2j63Uq_z2g!t4;IZxPeKe@7;ltms;QnoVs-ay{kh z2@0mJd_JJTJP(0(+-Mf#!bxD~Sc={#)dQ6qi-x0_=XVG}#f>-JJgl!Ij-w4!)-rqW zSbq5K;}QLpImVw(fCK&Mevs>L>gHAOfb7D!a}AHAjP3O)9w~uaa2qt-b=txWv{rb> z!*z=0Euu7!F3!8WzDdYWyMW<-(FMJ%J3(H-kOUsl4E;__fm=@W{&#`w4wukkJBRM(nxzZr*TFQ|8-pp8k~IDR-4^1+JK-+!EDr+v_-T0@oOGYxGXc6(w9k`?n111eVF6?@jvR zsBdr0?n6U^4J;fuD>%GES!~#Ja*>*hI&*;T`nsy7u8`xNaFIA1BpSRLgW`c=$NYN-HIUDio^gMeMqT*pyv8TRsl=GS#nw^8sk);X>T|G=*KBP>a zxoQLFOj=h*M^X{Q0{(FSiqpaKk7xN|-$yoYRK<+EZ{}wAu^jNW)0Rq@(y(R@Qe8Pr zScb-d6q!^?mXQMN@@O?-cV>K+M8NqH486Iy8``+03K3lSV~9GFCf#@?KUw3RFKvNgOATK6Tg%l9K z5^K$Ant>45Hq2H+KM)tkJJqddcS!mK_`Ut7W0on{9bXWjR3zzFU_H@g>czM!B}wQc ztHGNeg)KSN%q=}PboRK5zEQCE-j^8^T!Qg=jZ8Fb10zt3f*I+}$|z4zOKb!U3)Ac8 zn0dFrcT^1`nxKU*w(mF^X#0Arx5|G)C-YQd#_q%z+4YYlPcOfpNi$*1E>9T zTPQUaE2^lBP5o7Dub2x4G`?Ru{`pDC){i?Mu`{5dYQ24`9$t=T;qbG;ClS|esD=pA z)Q!mpnxw47^H_q`4&?|~CJNBx#3rH5P#g+cQ2`95|B4zu!sq=%A8{hsptoJOM6Hb<5DokIk9glIc`<@Pw zX{R*em=)F5j?<2!+tt@j`Ego2eimWjLp$+$Ye!mtL@}u$-$l`(M{~v=t$QyKW1Hyk z^JR*dWYD7s@4U<;Fab@7yw0KsNAw7BWi)V24)&m5D~la(T7JzbAf5HU{z+)h@bC{? zsICSpStUezBNhEhQ2lG*GJaE&6nK}4z~RopLAJEAyrKWjf~YdifeLwrrU9_zI3o$F zi7+J}SqWgUWK6TssE{(y!Fe>>f5g_^KVW;k;o6l8Zo$vHpIz-#nWM&63deg*%Z#R$ zSdE)-GBYx#8WufCu`+B!OOs1HlCZXrv90Xj9l2-pfo)(ljRKf4(%6atYI!xSC*|cs z#aHs+)wi@&!mH}Mh8YGv7B;Y-Il3gS@Bm>RvD{eNL>|Y=h37<6$XrtK$HgXdBU(u~ zKZ~HS(d7aO{lcM6)i^ zW2~_xL^13_aZ_?t$e|6y=FqgW@k)%s+H!G(n-#;$cR|KBl<$0}(FA1*af)$Wql8N_ z1i0W%RlH3*y%B&_FtmXxm<$WOC_D5ISKshVYWRqqNx_~IuJE%o_=%WtSTn`J)|XgJUe*`Giq2BAxP>Y(!!rn@_3rLCryY z4N@jJOORGPuTS{qxU7?L$LvGC9n(si2-0QzkwPHbgi$s-A@$_@3w(t0U86Sj7d`+SU6bXnRMDTl1F5E0qBI6D{s{_Ai(d?b;F=&(;5$DJuE9_+``Dd1{B3IyjDd0+lNg8G+!Y0>8nMu#r^w}1} zTblNdFn`x62}C^@D-XLUHWqy?$kpeu*GrQn60l4IwBU20yP56+<85I`hs)D!mspE1$1e`Pp<|EbS24^)NT&tqT2}F(0uZ21M1$o^#%6C zeu;l?;pu?~V$+F-$1A`M_`>k~2TiUBs=IWWlrOsLj{Z$!58sLPYf>xP`M#J5tNq;@ z@zoVny6PIkF!a>}dM1B9-;~Vd+1htj%hf8+F?S||^z22KI-f0e9EH`kA5lo=MQ|w}yIM$}mKxc2Jhkq**G*GzSjLpbR>Wt^s-0^Mlik7fvrI_=hllaC`g5Mw&TDPIE>3mN3b_+1E$#=ul1Est8beN8kIZLdV)n9nF{8_`I-z{rVf2RRIs%kjf zk2+d3jN?;w=bwgJ+_ou!{;bQP^c56&u0JA$wY5sZ&VOL64Mym6s;Vl?OWsNcpom$O z*w&fC=65*9X@z#5^g z$WA?2{e3I(GT{sVEn+*Fh!;It2xubYZOcs8UpCBTaswn-zWR>~uqNZIXa4BJ>=j!T zS=p_So``2+g`>hmW}cU0B0sLr+|?52Do>`mDl5EX0Me*~(F|oN1-0uGmj?-F0t2Cg zs=>^~9}Gb1i`qtUzAGjdo#a_)a=+l+6(hLt9Y1)LY=w5K;LfbRS(UPFb{ig>4*0iV zs-~T#>uD3YD;ct1Qyc045<5V*iiff~vF+a?4AGu+&rjILnw0e2oVKEV zG#DPyVH9uGgk$4RUzo-%L@dQq-nS2!JWxIcdZtc5!U(8E*9Y=)>x?fh#~0Gj4E?}G zVU;2_!Y8es&bU#`184q&wp26PCE2aoaa+ z{EsK;R28+j0vXIXj|^#C19%XVNirr$PTbN=Gt2~~0dIa3f}7Td`~O~KGc6;3kUkSm zadReWK}S}r9|$K@pESX0H5{FXDYzul&{a2dUJrAM`e{DpCi&MgmG<;+^yMIDPtNpN zm}Y-b&IAsSA%w^wgB$(j7$(BmR5W4%gQTp@P6k~)a=ytcHQJ#Q6KDsS9KvAf= zBlonWzWcG=mR{wgFK)yl*{z|J2>bwCo&@)5_V=UlLoL#IqcsR#6Z3WxaBp=l&9;32 zy-`$CtvZwwgIBH1$^PCcl!*8`^0|DgxF=$XHzBE!TiL(2rl?Z)ti}=BUQh`BM710- zaCC7*@5vKoXBo+iQU4uPGfiXls}0Em#@fHc8{F$SJW7`e6+FBqavLJoD_W_)HVD@F zH@|vmQR5?F*-?&`yTEAtyzX7&NrT8|;miEDJ*n#)g!|y>B#ps{mS@E3Bm7x`E@(G$h=a-N4g+TtH*>my*DO2Q+ zn+k+$zTNscybT|Z-a%F~r#PevEXTz=b515u#yMLX!G^2IPEe&X`3}~@=X#w&k4R`H z$Y|~KL~!*2U+Lq6zYQQij#e+4beA}eFPhQY4?85OF>wGW@@sJhDhh)o9~%Rn=PcbE^YL=ghX#&IGL%i*3A+Sq7NSS2ODLs&+lezs z443GtASA>fXt$gE^+(p77nU#^R!g3b_5mY`VI^)=8%>o*w{Q7#&ebxOI@v)GvOYAT zO(n>mpUS@=8qFTmsd@!3E}X62y{j%NT2Rfyl_j)a`+{aYc96&ku1(HkI(_*k zZR4@HOcWH3Q~`WsXX|#Cmk^Yi91D3<>YwAIXh^dQnJ~!<+hR=<2!{v6Emg~V1Vw=* z${Ku%y+FHiQ0>^vsFr&+SXz2_8YF|2WEX4|c3qlG#hrm};ObWDs*ZDpdE0&^*8FIS zd_*izd-GArBtXq_0VF{M%Mh6+MS->c)FI6mC@=~+Acehiz2Ia1@x_}+-S0YIzg@7X zay{gR&xv)NRfTtiEXAMavo?*H#cf(PnK_q*W(uIn?@iOpbSUID_Ot|nqky=G7qjSh z!1Y?5P&zYiwzWMUUYk%4@@C~plR_;VXQtE@u~sbe7+;+p7lLdEJIs`OpdQNeb}nfm z>2+xRKI`VHLz#-vm{1(^phTDlF;k!~^6h-vk?<68TS1-mnsQZjBfRlfudBu~>a_Lh z;Km{e{Xc~3#oGwLu3Krz6WFC6H><6}r~WuNKPU(v9Bnd5^H??CdnWfULf;x0w&~^) z$5)fCjEZg#UpbS(F)M}_FWZek&aAHQ#0P~Bk?xMf`-BDhtwm>Wxvk=BXdQuPmKuu! z%hgCwUgW79rN9`U)Xaiwfn(KWvPnsd zdjhG*XQ>q*p79PkL+?){)IT>A=>w!IW7LE>kKj(5V>N`36b^^xz>ARQegNTTFfBO)c^^Wd%q9pMc z%tiRL%nF!JO3tHZ6#ezw=TfFh;1S^M@a!EWzv1(gT zBdkXWhiB{)&8=Uh_5eV(TY&uUjAP!>`-Fhl8ZBG)JfJv0P2LG(nbQ>`(4#2BzPvuE zwG%r(9uc#x{G22pfZ141WNN@pd-3L*gOS28_@RpwsCkjp$R|I*JT}Zm(dF@SOL^{9 zms+Sx`J;Z`Mj&?`!5Ui@gr_&;fKEJZ)gS%C?-`dJaSav5H4e~Z!r(BhRylBH`k`CR zy|&5p$XR~wP4{H*oi)}76P%Ibr7M-DSk);t4`YaaW@p(^i2LEi@(hD=n0WcoI}K1{ zQk1mfy(=-m=~OUv=Is+T6P)u%=2MEwFSvg0{;X_A6MnwVCPwVmmvG~jv>c}iT<~|= z_ght_kgcoK+nAjrQpmEeKV@KtnRIr&OMT@i`t;n(uTwolO(my{ZfUzAGMl2Zk(?7y zkvDYwj54sf{Qknqal*2Ob8Jvt{6CH3vV$o#;XL7Q|ERJcUls`YOTh>y$L^MV5xu_< zoj$|eTo}R+_ZFNXp9CtNm+cu{!*fH&?IinM^QMm614ep4I1|njTAs&~it(GWbf|vq z!>%ycBNQf~U31|SCTLS?Yp$nf^Euha`?0HeQXBm~j&Ta`PAL2K?OT|+ppxi<8=8y^ z0KSPG?jk*8sgy?U0^)2csjmQxyXFz(R^#8l@!7K5T}LJQO>_sNh_=ttCk?+;0+C8} zH2;>|QsT+DT(>gjw%VS-jN)jqn&?tp#ro_=g{##<4-6ET|EQy_O;m+E+X(#ebW}N} zTqQE354Ziq2psv6a6nDTb6{}e7VE2C5sru%s5>aZj>3&(OPHRhXkUz|)N(9O%}Qj0 z4({yPN;Trnpx>a*MpMW!CWbW*S(H~(ZJG~PNW*aL=4Ajj?-$8$*l!a~GQI0R!RY84 zG0BzVryX>5w7>~yo;>od${X1doS53WTK`giGFtrrLCDx4<06ThBf~=&^fOU65S?#Q z9Ao3`D1EcCf`U7%(tDREPo9Y8HU{_n8PmNw3(N5Rd+#>Y)_fcr#CF{e6-_2K4Bh!y zIE%S(h;wS8+fEalfT3@17>#x!*Nbc5jj_9-x59~Wn=_--6i18=7vQ;td5=x0j|7KsC z825jZuPKdxHIch5ytMvwUv%lNRZ2hxG)e9JyFIm{)^b;G6yc^1&ZVVmaKchKD5~Zo z!poqMiqT7RSyJxzjNgCpH;}^^qT}hm!dQ#1UE`KIQ1T``RLoUD7W*Nv0Ewi=>h@nB z?XZe^beD5j0W@r&Pj)Y$klY)&pF=g@Xn{XCf2%d$mACa;v3Q_+@ecOggL+$@UHY>1 zEajIXy{tmzrPEGbA?K&=iUMWpiRd1NT@Vr&S5vOp;rg=@z{65wBgy=>wNM&}td|8m zi-!k|qTi(Zkdqw(yJp`-#iC90Z`8x-BarGq!v|Il7m*g6svVDw3O_ zCbpuD{mB0Gj8p|snzG{an(LZ<7Tve}XsPp6;4KcqQ7FLFhPubVeQB@e-)y`mUs*gAis8a+1+*9En>7CTS@ABkH7NLD_+eKGjd+tE=LSoI?qBe(byU<6FjiRhm=FnFW>Te{8-!cd(vy2Iex3ALs252jAt3}2}kSNihr%8sK8+^RX{hC#J2<(gR&G7@T!@Sn#` zZhvXa{CF=#?t`{C{afm%65d5bxWPum=M@(dC8n?Lrw&VsF86M-TVj zvPyWxZ2@5`yte{2z7iO#E~FXCJ+?ARL*ZHGL;XcSZ%oQT10uG$L@6b8+dXFMfRZ%Ug#ondSaAu$oiw+G@T`ZYp4Eq z(&%)y|0M|BmdT{OmX1~VsvyM!?iO3n-f&_`U=fd~`^r?1fRx2p%3~vm=(T|_UN6B%n{ZSGBKAdxHN11plAvrd) zs#Q8BuXY&j?O5I8QtgdxCB`Jj@P|h|9}YGTc%q@v{b|6m&eEG-);=oE+=OXx<*HSZ zGxO=M`FT$KeGZ<53e0v2LIhT-v0bTE9COnv;}H)mezpg1f9nmwQ#Gf2`dU&DBjcTb zfHX2^pxa8K6pQp22LaF+MXR=Dk0&z@(c=JLf_~&CZr0wON~AM%Xbry^KT+FBxGOzRSr?_TUf}986&#%Xmw_;~%{A3pyqjEzh^g_& z0qh5*WsW>DO-U0itATV-H5~$$JoBQs!M9W~wUuap3>k;|$W79Tov??zw(}mSs+~9$ zbXTR~!t{easL>|B3A|W_URE&~KXC?j1;8yv@rN7tO=&4XNkR%ko<^YxCf-F~&kZ&| zFq5^-^7S9g;JrfAiJfTZ+L<^$N=~`u1F>^McRE{X^ukai2e-2GU5lK!Eg!LE-a9$} zBI(1K!tKOe|BZLJme9SE-rZZ>QS4CSMdDF+i}KokMCTq7Y>2{3X-8Qa+Q5IscX0nN zSClyuT|~#auv*u1AwkFh*vb@--0Aq+dSVujeg&KBn1FLnvYVp3; zM)Y_Fvaw+2Idm&JS316>5}+pJ1G!1V8UW=f5((k1^x)U;bV&ET_iKhm85b@Q4u_K^ z5oG`(n%WxeNnuPQnyx+8vCES5cawh(Nw~&7S9#W9%P_{~%!ip{f!w6$s9xco^_3-@J;pn@$6#zJY(--;S#a!KC*cdH8aDNaa1bF%u}0EHRa@T z3*a$FX)#`Ru)jt8Wy)r20{QGMS=-9hqEaQ?NVB@k?p;yFJK+OhA>RYL2{;z+QPekd zNtoK?_~(xB9#y7vW>h~?u{RyJ82;k$_G(aa%q*QnJ)h%k1UmA zKT)_mlj7!LMTi_z3P#FT#4hwPeS=@a=(bnODU@v+Bk$sty^ywd`qYX}1oVeCNL=n1 z=cJRTT--8B&P3nwQG0d~vMM+lr}2%uGVQn~*|SIXxpL3?|8>(;Dno0*fNXlUz$w7u z*Z0AEUxklvXY(@TKU+XTiUUUA-{ z$anq$j}Hey&gUWE(4o)O0xp)*x?om>pYWq7d1J$VWmHI!kUkF)nn;yWz*siLn0Gi< zT@|rq;x-;dtNd#_HvH)hxj2<9Grc&HKOunTj9L#;N~5pZLA4QE&4ZCR;|?p!$@=;H zTxo{$oz(i;mPR*F81)92lEFyKFJU1UXL~L`TrM15?Z>o%=vE1d$-j$}f_Q-I0f;4y z`_Xhe?+~(dKv(dDy3S9%8$>g38+#Q{7r?iZ>HU~p@9~X(%>(c;_^8xgs%rnhy`|P7 zXs(vJw%n3-sip27v})#;bAH=fI$6xs{F1QO?M6{_7roHbuv7Tu5BhsH@`&g`*-M(X z`eP4QY!NEJ=%of4{sinnBot-R><1LCkvlv?jSss93G7+hX=pcMa1#$etx>i&jVe`Y zZ4q4x$XPu_hHqzJbRH7_VbOkEYKK+ag0U^W_K+wyE>TX_w$5D>&S`XMSrwScvi(l` z1a(ePXJaewnuR({eQC!nlJ9Lvt&)v~n@?&Gan~q659_%Y$rAgc{;I@N{JBaaxBopRE~`A`>h5HxtNh`A zg)DSSd)Uiuq9;#K%c5g4B}J{{(dxsx8Q<^X)G3=KuGznlrW2sbo55s%y~Q)TSmp@l zBv~|Z*F6js2}mds(;bqhx;Q;;@tmD^@b6h2@8I6uRf%OSBS2I+m3O;P7>1FF6!4AjRKp4?r?hfBb)R>+(0{{XdmcfQweefH7o?D$%Eb=6~D$5Pi^h?|LV z+U=uauGF8oHZ$)GTaohxF%NsEYimsiKlN4AS5FxY;gdlWbXL|(Oly4`192h+Vpk=( z??A@h-AFy_*a+v@i*fbzqx63(Q>RP$3|qliEx#6HQ~3-&=;9(is~lZf^K*A&qtR>S zSLajKqcoGy-_}fbl;B$@pS%VM-y|$@tBgL47sv?5+g~e}lMV>Tcu-r+`60psHlr6} zPAX&W#tzl1xE$6$9VN_{D>lJ24}aevb2a|5S^c8cN}B5{t$8K+dD%WAdgbin5YJF9 zKaIVx7}kx>7x%O(GV?RRl-TX-1?dEp-ZnDPGU~6ftW)Ea@iby&i!&z$J>Id*G3|CK zaj+pUx9u~ox`!@LfKiFh`dl*rTw&izq?G0rg zKRdU$k~m0O$qv0qP6aSv3PJjUieC7c@=)A!4+vA8W@{ zH}d*b5_;6p)_c<6SYSu8R(4@uE+9U*vt>8~@e`c7w(nO#!=&?<(@{-I2Qy=5!Se#K zs)mk<`F)dv;h^nictCw&e`9T73!VMuhk1jF_QS|3GLzF68Qu(bG!=W(*+;*W3mx%& z@u=z#mGXc7d#8mPUZKgvJT%m@oTRT5)`O=bo&5}R3$5Oa5DU|Oa%9_R>3A_oYHrQU zb_}iwTRHd+X;!paIi~M)_;=wGpOC5c*B{Q;ZitS6_#5%j%Aw|X$VMUf&~TfajhzX2`k zaXNvnu8P8eMx27`IxLz!RszBr$r|Zi`o4Q3SJJ6x^Mzqq9hrv+Bm|X>hjjx(d`H`tgMHT&pf6Q_NSR@g|7eYZa`$aP#Xh zaBF1L;DaV}6NO6&XNNu6bw2vf0+kBBeXp`V=LsYiyN9okcUzL)6t5ozFTneKUL{p% z+^ZlinJlg-hYstejFNM7tdr9b<1)XTucLW+RH z>;biZz?ADW`e~JU?dpH4YQh zwA`b}d(>6ZIQ<|96^~@pwDz?ym0i%M0N<_$+vkgt)7B2w2p8#VgEsU|KL)O*BfIMk z4kYilHlt-j4PkCy#cBHqyRRRE+Z!9rz{U*e0PPK5ln?o!{9)@+$V|JpqL3ub%f`st zes18lXW<(kC>F`q2*h|nma1PCb=WDu8|`Tv#$}Thz+&8y$=(o}b5kxVzz0@HSW>JO ztVFo%Xy2##glcOg4+T6(n@-M^mwC1tXKO0B;Jo|>=mjnVgw8xy_(j=)8zvuDT@?nn zT`je#Al%5YB8BURDu{W9k$yr$3R6lD*Q{vL6V9Pw+Y8AHr*oIXICK5jH!qEdHRn@P z4+FkySsAwx#>2RWjF=PK%cRdHPD9Is7u(PHI<1Bbz~yKmyk12>1{*`+^-Xl$EVd}e zZXtSA=K#vkt9|f982Nch63*(1`=!TBTtZ)yRdSC7nbTS`-8n`RW> zIXU&j^0q{y*e5ML{Vo&6qf1zKim{YJW_MS2>@ zv)=FvsQrZc7y0q#Z+#u>&@{p|`p5AGi;VO)xTHk^4ZQi!p@KRob^JJM8&*9={(gx7 zY@aWYh%av=OE0GaB*n7uGYigal7Ag@*Jt_yvz^Dk2O$Ghd>}t^MLCUVml~(vdmZ9}+Cu_O;r|TK4+eOP)N@fgmT96h424UVcCAcW>J^ zf%`vDq47VEqy430_Vu+qxE-|&u;^>!nu=9B%JaT!z=h8^CkfB65}sL+Z=?MVP~-=w zR)B?Ydih=j9*o4<+~18;?7w$=h|a#+31lQ8;YVx7-!tQzoD64Y^ApzUJRT%&MRlH zoH{B^4&hJaE_fG6El>(h6QD)8XI5ek9-sBxAvnt>Lgf#B8xXQ`yl8Zqa93yTk3R8- zYWpKp*v&&Z6=?tMgqFkb7yKJWhua@~v*3%OF}SV>NccmTu}`foRlgMLVFAdi=Z+?lSVj zJ+D3xxcm;|h^o;nHb+Ga{<~F=)=%hly>P+ntD19eIsHM##CQEh_F#~hCE0}Wx)awO zdlR@FOrHKaz&TMENxAP9U@zxufCrfXRYAMDDSBd zpLBj9kP08N9D;=0W|(@lgj{q^7!1e_-h;ATry7%XA(BTS&Ml6rZ5vA7`nl3^xieyH zAD-*I@ZS3H3hisAZ^<~X#2g>QKLo^eKMxBzoPFQm@cfMq9QdXAXhV#Gj(r1bF|!q_ z#(|ENTWS(KJy@kGQN7gTyGRI#Pd~bBxx}9Twq zhrRqX)dA|84J|ceKvzIR-FQ{>7Gn+>B`5@#aJQz8r&|DfgQt={ODVRc3})?$#yfO= z32+T=c`(N)w_gk)jBl7P9}>p*1r#JM6u%n#4gf*0aR+M$ii= zT+iP!z$T$z{btVupUYf99}RA`Cjhslh&5y=qnQDk>+@8Wh=!|%$8<-p!<4K5RurGE zH*?kc@-exH2%c&zxw z>gCDXda`KaIRQFG1Z*t&S~pD<$7bFTaKq1^t?wnLO^#Rppat>k3}>)L0#_sUs9=c0 zQ>E9kykFV)93)0S~=ch*+%_X+8glDX-)`4VI+B&XGq8t2$ z!$N#jUjF#ATYrS{9#SXX_9Ah?nt19mAEwm4t^5|;aBcOBRcKg}mNn{sptk?Jqfw0b z23&k@X3a0N;O{LbMz3JS*bW;`b!5UiNfmPaS}TC%BH0!_docsAtX~Bc-9kAbM@AiW zdOrq?{9t#%EZXSxK|Av$E>5ktL|jAgiNjl?~M)%SGG?&J>0e3{?Ov*P=AC)@eT+VCFv^^Cca4#dg?ze`r!w4dT9;Ql`CUlG)V3B-O8RM zHbFZpMb!roYQ@!S+?3Oai|RVhmZH9x(=9L*^ed5z-xY3p;a-$%nQBYE4{3vImw8{A zqUP}#gH*B7%Vt?$<0JU3BZh?*4kBetoNgK&k1CTo_tr1>(jL6F=(xM8Cu-B!G3Aq4 z%bB8;@j*mdS*}~bo_oIZf(*7A?4hXYjJHys6_$08g<{d6U*sV1GoRjjmE2C}aDs+h z$7;pD7y<+QPo>Ac7)_T+>OZOV0368K=W_Y#SYI;xR`Sx5hOg1DXgv%RLIIl>18`DJq)9+>^ZNSx388__K^4 zt|V>dfFBY_+m0?rqFxtyk=RGB0=jPB?D7I5u#SY7lJsmksGOmL!w~BO_dc%=A;$@u z%|xf+SfLVomoU5|pHgd}&A)>~|ae@p&u1ib7pI3UzW9;Bw>qmMpiifVwc0+tPkZO5B zdDVC#oSx~JE#R$Knn~-4OP@*DpbN*{zLT$(P|^0Y*lo!k3}~{d0X2l|!{n3u8dyc- zztsrnzy2QM9Y>xkcUj?L1OTsQQZ;@nJ&-AlLoJ@5m9Bn*xEatfQRa}lPkjHHjrkt- zK!wfOk)Q)dU1*})lvIo9r<)R68`XsW~&jTzCyRR$R?=CP{Pj{Fl{>(VCZ+HP4uzaRVOMo zhn%^UucE4EV@b$Lhh8eZX08#1k%hu+w#XEImTK>K^ygg=JAAIhE|00LN;F+?3i64K zJ^6=zx0PYVPZgD)jKaRXO@qFN2t{dWH+tsAD1FRF(>E4hl++{2Y4+4Z;R5>2 z$O^oCVEg%`7yYS%{@lDLxt?*qEu7zE5v=6?uK$@IV8X_t|wgYOB+cIjbE|GWF7gf7mvhBXJM8TJ#DY_L;INYgBJfed{+( zawnnCSb35ii-yl=od1&97r=@GQZb`$IA5*Z^_K7BLmyaxKB!8V@1p0*RobqX$;Ak= za71=R=-`7W!1`1Byh8`;%o|wGqSEErdE#%~sTuTSNriwFY_auetFG>Lg@>7q1+X9+ z7m!XODTnppnMr3$#NCSw%Egmap8wB}g}?km zK+47-#i2sGdy!vv-|HJ1WPOo{Oe$e;9FVho%t&-TD|5wv?j8&$su$fQBKH#IF$IGv z2b67G9|6(l^?iQI5bb#25Jr&*d=mvp*3Fg^*r}V0F<~fM;UXvB8uKKF*fYO;atNlh z`yLxXtTOyo1d|cdoD*`Q7*VKf>EQEm1&CL@Ihx{xKf|L_q{QjzWvTqt)u__%YL5}^ zW?mE0&MK$`sj8y(0-grMYeZ?#M4&uiid=Gp5useM-77q<;8yLQxa7>iAN9pA%VFcO zN5zqhn8=zHETd}$7wgo3lJSGQl{z&^q`r-z51~BZO?kRnSE*!Ki&4mjAF{4l`CdlC zGNMS1w8)Uge)(tVmGd zv=_V0RVgBu!i}#W9uR_MoCY#Px+|ghptnHhWi5<=hEM!pO-fz7S|!n-`9A-v(vZ97 z6T3@_SF*h3QANNAuv>E$i`t~GdQ0zJ_QU>-?pXO+B&u!BwS?_q{gRn`B%|+?G44mR zmf8Fs(A$E^=$^-Ub;4z1eLkYp9M<9T)cK_KDNy(K%!`9u1WmIB zF8Xp}(!USH{Z05~Z(eZ~K-TX))A*Qprm&oN&Q%%ye*=&I&wTuD85@b+?)dGAmw+4t z12O`cMj~gJ7`H?>vK)s=5_Bc%NQOju8%i|T803(^dEX+-XH?`>5uWCUo+fCqr;w72 zw%H~*2UKv9$=(5gZxkXBPpnK9Ymma-wooCd1L)xo<^!3&CwtThnwiZNCw84r+@|fi z<4wO)KOtwSyt=QRwNPbLFa%Huhi$w)m|k0h;GQab$t~VN)>gXbBo?NeM?xa1(>ceh zfq_E^7dzk|4kyG-Hg(EJ~*o7LWXmyueizurOFocz(ir(mFq{Z{wDxe6^MnyMLTAd3T$QZ0 z3p1?6nqczYhzz^&x$n^K@kKqAO&&=L4lUmrKZIQ>3AD<*Y|Dt5l6Y#ty)ABxV{RQm znd((qnWaTB%6L*2xyrg6SDH>7AIr|PivR$J=D-Riz$~3qby+SX=_*i)4 zzSi+9We!^+_!!l+LTcSQVe8M0;uQbPmUP?OGqi0@m8MQWPz}o?2B)LC{ju*aGSEIR zuU{j(&8=0i4aEsX{!XThBImnz{*U$2TAEfaAlO}n92Wr3&X-q2vSG1-$3BX-JS$B( zoZXop&|~=6)t`A$eT}t+G>#~bF-9ag+AavEyzVDQ&DJ(uVs4*v$I{Hw_x@E_Hla&m zIGdSlV!>{Cg)Eilo*e30Bgh+q@dG_ooglFY{UWD8JQl_(DoP4x5Ex7SfE{0vy?{;E zL+o7NGl0vKPTob=nyeR42KT#Q-e+j;gT_?%3e-kF2Ti=@JgLWOXGA^wX%4Gth22&X zz>1xqyQBd=UYpnHaP&e}8;(?nu4;h*V9QvN{5>4rL4$HpstmF?BdTB{A!s|(W`JdK zh}V`p-Q$%0xiPu7;f2=AS-0q~$WQ~7hgFBj=5q{4(^r&C(qwZU{~+Qyx3gd9_Ph`X5$7Dd4D^rkLLPcos+ff{wkVLh*R9 z^_6Z2xh_l!Hda#RSon!dDQGLXJcp0B;5nV*Xmwdvyq_7yglOk5LdX=L8=uD64^bR}7&G}EL@m)eb?;bo$>xJCYLg>A1o3SMc|r(dr7W!Whx zdv|NH#@Yh4xLitOZ8y&9ip;8;jaz9Dy?kZTM|AuB4}!Y5s;8;JF#TT8ql`Y;{U)Fz z&K5Alnseh3b>clFVxn7~7I$+hZ%X|fZuIRrv+rE#N48a&M24Ox*_5LzJ*Td0_HZ7p z$09bASA6F!$E)jZ+rsT1o+Cyl-y{#0C?9N0`Ii2);O5iK6iho+ zr};@d^$Bes+Me7zeK?fub+NxPnEft{=kheT;W84`@MXUIC9~&Vy{mH5h1=-dnd0(j zHL&O6d!yCfNpybcf7WlRbys_LCAz!iv-|#p!t7n7|1rd`p7H-_dTTP5#Nww0 z?nYSeSQNh)X4}e*hm-*uk@iRxI8I)-WWL+jBq#Q)+3r;#Rwg+f`9tf3!^ojlk`~EE z`82s1rU|D^f}31AK;Bhntlg%-yj4!GVNPRmJ*O^e7WQYxbhlQ&AyAQ#jp!?5#q6PS zCspHFKos~2phwU9DFxPh>Xz1lpp)Z>6X2$FA7HXG3i?@)HJ|Xxusc~oqPjl-g~H~F z(x^EVX)d!2mP}1dB28Q)QQlwE8X6;VBUkH<+a2-;q%p`;$w|RE`kkA|8f}Aga(Z=p zw!?m!n(m3d!q^|_!5uN+#kXEGU#cxIap`bpgjMgT|aWd1Qo&8$RYjY;tj-C_SG1WJjs+QVs z*X?D+le+*|H=z_G8N;v0;Ic273VuN=$awU42}Pfk&@99kac~w5tA&bNGCMdWkP#8>Rn}o+T$J+3o~Q@+sXOQ5K9i ze!&0M=x{#^y!s)0^4Q#2dU;=F26|Ai*~DA7Iqi+_`xXzhhJWv_ftb|k2uBkH%LT&fVciUTt99E= zKq`uQvrK+GhmHe<`qi?%ZhQOt^6~}j zb;w3%KG%kuHnjPCOjvF0^~hY>i3GP&Jh{UQ?h>1vJ0ta|>7En|V%ragrIJ8BCf|YN z@!tlFUuFWEL)FnY?>IE4nvkyBFs+u^6cc~lB$N)Bnp5dW8cQ)sobEa!aWT(3rql## zQ0vBd#-BES893O32SGCv{igaE+v-ZsvHaN7(2k(DbY_X4XJifH$6Jh22DYDdu;Z># z%)^t6WE)=zBwW}>)SR$$jUgVKuiKSaer7lp#%e;Vq+|}TbQTfhPZG|)z$Q!^=;i$M zPrTfM<7ry$-F41ohx-IJYvIgfHW_c6GrH)LB@~6Lgn~So6z?f`3wLLH%xr7?7<#^& zaNbz{jd{(Hrnxb`D!grNvF<5|?zCa$x4PUQ6?WF^`i+^0uKb!dk(rdEjFtsO%PkqR zVKfx)pR#Ne57tfaw82qX@j^T-DH+y8Bv8(!6vXW~jsFxgr#0jM;8XvBUxFp@{iO51 z!&?4c)MhmiQ5*>t{KIX#l`#}Fs<&o~Yq`V2%{06sxw+0( z1!^#3tDO^_eqddM^*3tt2yk6Nm%WN6w}VMIH-a`~zOJDF&}p5t-eu1Xo`9%X`3bG{|Txdi?#@h%n=|j~3;N-&3)s%v4Oa_B3U# z#iJi2r$hkG&ducN)yCxh&2G-{@BzTsgqsbIrVGIt{_{izmU5!kHr{TkVmE2g!Q(M1 z=$zwZ5c{DYlnM@II|gNuTDzKFO&;cO9*Fr+7if{5g$;P>*I%a_67ivUcRi!Xy9hNc zZTOvF09bN{xQ&ZrW-6NF^@+?kC`uhOZa0>EtmbosUKU@1$DWFD6{plkPCm1Cld2MF zUgpE?vQpZHc7vJ_c=oT1p$3s6oux79?X5*Bn;vFGF^JCA{5GH9(x;qLaUbpr*XoxX zHH+;Z{8)gbjPu4r?vR5L;*0n(Vt%6GLit@FJ>P1O_$Bl*B z+S=70L%BnBZ;6{|cYLq{9w)ajMDiV~&u$`a7LFhMX2*`Ntz0#6Tft|MIR)vERc$(Ut2&x@2Tg#@; zFYGr;44bfJmdyn;rl$}aJj61ynfZz_BD>m2{nnE#QzY&kKvIuRkE%=+68G-Lq9c9D zW{*@bVMU@eyf}(RS!YbkQzIdpaGOm# z1$#I*#l8lFipZUHTP99fZohsed)_mK4J-LnF%a)6+fL#m5Cbe z)<`%^z$U|c#tWi=7q_u=p4oK9>2&k-co>`<3dBEC(YEaQjaw$N$whRAHe37f8E-73 z`(Aw+nzXnjI_}-|LNo}FwGs`eKmgFz3-~x7Jn4VHIv6pT4rbRUh``he3 z`1~U3WYV^Ay&{1Ul#r%&V6SS^vHn6tw&7s9zA+Q)Wcv_T1g>_hhDHo^#0(Cxyk6U5BJ9Aw#Mba zu$`LKH@;I{D`mORm1F-^*}q**|AyM>|MATI&C>WJfaR2fYw%Hh58+ljEzB%P+iiBr z#cLh&ca6Uv{#NGl;MY)n^ZGh-lho~XoKdl_zUW8VES7A3Jl>(dDo4PkKQX?g+K4qK zkO9KW^>(%y@L;15pUlQGLcy;ZFuSk-pC@Kn^ViP?wm!2CdR?0$({iz$db-u#ohTNl zQxsQBfn-3+3h9OHA9ud0x66GcB_4;!q+?+*Q>pL5co3J29R6kX99H$HF}9CoRbz+U5Wg1EtKgpf2e+}YeS<`3YFCwyJ2xhE@9>f}SGcuF~>$Tw$Yq4!ef1I;9!K$BXfw{ah)`^-b# zRt?lN1XIzq46DJNHpjobJ^4%E2f{ zl*WRhq|&rr8cnWq! z`l4Gk?!R&Y)bg*8@tTOyQ)bL?DAZrwN62gZMgv}iUD{9(A_VW2p{JSnqu==kPG)(X zebpD@M|la=M64ZA6+LvxGDV6bS@=To?-)_%iW7dF(Uf)w_6n$DZ^znf$3nayW!kxY z)yDZqwfi(>pO=hjs^6LPnWW_{1W54C#GBazTb4_mFntK*c>d5BqDl&JDaj&dAiaA`$Dg7G^TA9A{w^yK~hk0545bl zC>1-P^efapXv_%zAe-%8(zf|Q-kC~BTTRQxdN>jFprJTX71271M+M?4EKZ*)5d!wO zH8>cp8NQwPsZ-H%`tK+m)xGyFw6rG76|NI%7A0_I_8ZaXpQ`@XL@(am z*#ccT7ypw|_m5%VZ_!#YWDT4K+5d}3=E|2}^0h*CEE`)Yu_^@lYZr!|ZO4`)BfAo* zoFcA!pT9C}Et0RJ8==vQ^tzTW)-HCX48)5HU7;YSm0o=GNnPWc{nh(Mp(ll5HF0sY zzON?BtDKKgr{9zI3S`dp(yu;eyH=#8-{Rt2UzP(Eu07$%m+U5w{&>4? z&a2MT_hNva;?(EC2n#?-y1I0r_vTI6M{I>h8}%Ib=*7IQMtP-qiBjH_*A;Gj)ys&p zzuN+NuewR~{F7))S^Pw(b}?1$SKg^U1JuN^Wq_-X5;8jSJv+0h5P&M0tOqW|uI~{{ z;$U-_QRi5`KbH6O(m3M4zx==aD(jPx&mNV-RLbigxg&-WdG@u znu$|?(AU~keoo_ywJylmN*}95N1%ZZ98z9WRYPm<#b3f!^akBEB@z{J50?{I2&H!s z3L-tZoGt8q{UqzTP(Qb>Bxd{^gt2;vZ6v!>I-4r?{ye_8lHGC=Rrq*tDtu?;K(>_5dXIAW46*VVkluR*gkAuFa_a-kuiKpH}blEdRJFfZp z-De#?ZmB9Qica*=RLP}@-VGireC1fWUV0Hi)>V#y{D1(cSRxU7vm0>?joi6yV|aG( z`g{uG^sX~JXZy=ifU?#Jq4L7Ik8R6&Zi_7U&CM`iXxI&mGq$D2#k(86c)kDS15^_VSg#E)Ad`lbZ#RY>K+^9(MeU{S z&B32nc*s2>6FjjS$;W{c-7iJQ|8IGmT z^eIQhK0~pMsna?viPB>ez-d)|Ho5q#*9mjCiv1P1%(?*sO%?2;q{L1^HYtf1%R`8I zeQ?iyms|AwST(v9=tb^w4TPPR_%6YHSp{qAE6mQZTI0jB1v%n1F(F5^;Lzk%cBs94 zrPH!8t=-IA^33O?i^vDKlDU$#!!|(Jcryh={BVvjw6=Bpryy}Bm!j{xT~zs*{a>(Z zoiL}IHWB_D8kt%D+LUj64nt|7BA6bM&rqdzXeMzTZH+&Z$4}~Rk`6|HpSgB|PQKsR zI#c++sm=dt(Tl&KsMuFw%^KwWD_{S@{x0**0M$4^y!Z-zS<8T*dg@{ycv}kUB)4d zJHa#Q$u17vPjxzLh;?maRKFtkSjKq;zjJHQ!D-~B#JSFN@2s6kB~CtK|77vl!o%hH-ELvq8958uo-KKnh(P$!aBsa(G* z8Do-M1j@E7vBA2VQc}QNovo3@9Ywjqf|kNL`eS{OGbPJaUIphsX9%Z@)%=9$Vc|TQ z!krr%GgmX5M(8SS-b#+r%;*9r`C5_zkO&Vch8hJLZMn;}k-GDt!O~$_ohj}pp4ybb z&#WVHt<_dA{dmTJXzdz)-KWASZ^l0eEbc$j2BRk_i3m1vkT{~HzlM>DEW zC&SF`@>uggJTkFs!y*xO1}Ce-<~AiPl-3--%dOs% zqT0BzT=kK**$!V{j!m^Y*m!vBN&HX1=g5K*6WA=Ecf-!PU5~38OSa~ig&2nL^`x_= zJnF&IozX2N^rX90d%(G`$fy48B;A>#ULi*8T`?FEfj=O)&FnQ)z>{=CN{B)|EN3hf$ag^7)mdwofx8FJY>hJiNN)Pa>p|X+7 z3&(G)nRjB?+vW$f{s!vgEmW{wU%0Qr;Fgie!mdB3>yJR&1Zkvf@yMq z2&neLjC_>1jJ6{IM-6*7>(TXtH(4J|y5?pon0Ru&lRvbBo+f&agIXOOhZ<ZStP@^~etT|y8;4D|puI4XBTJ|2j9Pxo`Qs zf&VyOy@LJsWfO@}C9=IFqd(2>+b2!?+T}`uvc*;laj=3Lu(?va49v>E z;Naw}CNTJ)6gMkB+mV(~deIZPbVJ>?AxhJbp#55m=2<{C0_wlWiJ0Vedh;=0!iSSJ zGqLXA6XTEMQM_VnuA6VDsfwC#MPocFA~;kf8*GJ8M%a6|ltrqcsQk+@JseV1&+KXo z)jdl?@(a{DsP$I;$uZ-H?=>~%Iv?T)<^o4fX^pL{IeB3pq%%&Z4 z7iLAHwVg`E9N`x0XmIS+u*KeH^lsgkmBm}Jti*>?@8n}kgwC@B*AQW!3e6WwD%l?s zq_}ik9*oBg)>K#CQaHeznC&`|Vz~Ld`Q6~6HsQvY(pZ)gh8u(qk|%Toc=HLb`eyKs zf<5pBs#Ue*h%gf~zP`V$y;O2!N!LYHC#jd!Mm}I=v{80Z0IibE!Mx2om=ZjBwSRH$50RwgTrebGlgbwgnZmhH9hAf!C7>b~CTCoi(2eY(Fp6}k4%v7?RP zi^O5*hV$ED>%Y@ux?7dW0P*jKmwn$2mEBh!K31H!nUR0=XQ?->%&8E+c5v-l&wsx} z%Xa@lRDb6z4^N*h{#XkneZjelIS!#IBR;`K-;K2z-=Vx$$6gPU&Y7COf7&nCAp{#Q zG0Y;*B{zI!`zjFd)g<_LTFUn2#Wo{suFrZVb35(X<;FAwg|S-Q<)Ej|5Uaf0+BS+G zyRljrwubMEwc1D1lDVC-ej+3+oRlw!Y+t|y3lnPCxHH8$>dUvH^j;r>>`TIXyuiIxpu=Q7DwedCrxi7h9g6{_mY zb!8ORd{)B?tj2hSvFoHFrs<8Su6ttGTKD^IG`8N34RLx}q`5%n9hq+g?{$*|dl~ zoU$_AiB{Qv-pIvbJpWE`Mm>v7mE&r2N^v`P*#}>0tWD;{K zb05cWV>w`?%s9EEMu`LSW%ul?EIIo8Y4;&3ZG!F-2v@nLA(oNe)l6`y^75qJtnC2T zt`88}`?1#qx*#MZgq@A94%N5h&ju6AS2->hH(!-?{y%JecRU;X*LLidq6=+}=(b0P zQM+!{QhSe>4J~5UmKeQTRjaMpBKF=Zu@ies2ZA70L=h{52=adJ-!tCd`#kS|=llQp zT<4tYI^XLMroJQ*T01rl%DSzCv8{L$IE_W#-*&&{rpy}~dT;fqOYpWdJD>r(JFIniZA&ZC! zEoSfy&^0Wqi{My)!S*fO_8gqfw@`~KyH<0a`LSh>U8|@S%RxoeWNgT#=gE0vv9TeI z)|&icj4Y8!2Ub@A7n{yAzm=LR+l)V{AF7T$l`*_-D6;VJYld=9+Ms4!)U{!-AhzaG z&JgPO0*B>`u(byt+uP>cwyvDs-9K{ z7^D2kGR_TI>dgNrK7h5yv-#~Ceu7gt)DeXE9n~mdDl8?5@;150WHgN+9B8q;jJsta z6QMfxjTXr>@3Ped>9W(<8ihUmhdgN_{OMG#V5CSK)c0S;^{j5QzlbDn_@rliU z@u{%AEPKG7#TC~jZJI~)sNz#C5(`tVt=FfeBGs)z0k^8NnyRKOc-s3$UdexWH(+)w zO&bw-eyGTpQ65W3byd+7-i#u-W!$(L z)NIATFT*~-_QQr(01Q$_{8YE8NJlLzq3XkWE!s|YJ1e823rWDU&g|5{w&iV{by^*2 za~M_DcDhYh>8^d~>N1Rk4I{5doQ|~4n|XE+j>~?`Mhyr*AEFk9AJbFqPgCq0oUk?e z2aKPb@EotY$N1EPZ7-%f8@Z}GFu`-La%y=G#4l@{efOoRmMC}S=P!@ly)d%esGB;8 zCKz?TvN{)uD3E{y4~J- z#_jEPv0RQ(tyVbUq4s~AT`b$^LgFdZ>} zfwdh37@nKGad)TNIhA{cYd7vNeT+PN!p8)74Z5#t2W|Aj)B+G59M`zbnw)Gqq3_x< z+j4VnS|wy#jJ+u(h<^+mnW(Dy`pm!5jN7bq^y!80s=Xtx7nGk5heh5qSrf(oeQHKu z(Q?3%!3=`G=hGeJbTdwrmcN|dtd17oz7=lrzg=Jcn~>XinaOS2QDbTsL=z;m`7TK5 za&kB@ZgFvPS%eY+PTj@>aK+HFxHVUiYk|ph8sFKQ=EVhqDrmZ1-KaMc;X|LpP z3T7T>q?;E4-N4P;b?m3uk56x}eeomsSJR#mub$mU9dUr&ut!%!BBj%S$GJdBAeGF0 zKB$VH*#rv{HIQenW%#0QZ`#hS7B+zB_>v@dwX*Fy=L2*);zk$yugWT&^I=CCqTzur zSlUW_EjaZKH&sdy+_Yg4c!$|SEIZM_yGxBV!Ob6`9r&34>x#yA!4(9 zg0(!XvZYt(N!89!Xo7}-F4d?zb`S?$ZhKrX5{-JCIxc!tz{)@Za`6dUHDQT@S zh99yZbrnNu^s`4N==-N(D>QRel{p z^R!_?%Le5=AlKdS^hY){uZ^k~UM!&C4GG?^KC4rA z5K+aI&%KMx!P8IGOjXZ*sv(^&H+=}<*?A5v4kRHsA9<7aza_Cw1KLyZyaO)Yf5K`? zjB7O$Y&-rDsJ`S!k5_>_=`0!!uWwxp^6(hp?PqN$dx?ZR=ufb%W$?+kF@@+7YmL+? z*D;eGVqQNuf2ZmNL?A+XhCdk0qFXD^yW<`lnZ3vgDoca! zJ&)ZA^oK^72%8@n%Z|>HI|9TjU|E@vV#m^rsvy88s-O&e5X)qKLZ9#TqmQ3b$le+d z;UcutLY1G8yFC$ami2wTMZ;%?!PINVj+ne{~)ek%LM|`9|}$#$ue4HOIN9cO?&$e5#29 zsW>}{i)gqiKwZ1Ett#YlXw*v&DV56?TT2sd)Et;*rf^qM@tOQpvg7>`0d_rEnZH+N z?>%c!+hZC&o7vq;%)}fMNz7m5<)l*{#+IuFj2ZaCzLJwNvz33Z-k*ktoqfgFSB;U= z#Cg#EOY>HaU&8~1Cc8UrTumKsRd%SomJ?yp`R_l5`W}6aVg+(fDD)0si!ZFGeN1&goK4 zz%r+NTK18)+CBC1llD1-{g#0VU>lu@K=KNAZ$9O)vxHHIcu~tz?p6c@1HsT;<7H=UU7~26mWjH?v#l8o6w9v@W7Yp~DswiZ{=+ckkXA<^5<}eSCH7vHE7L)Xd;!L@|mR6d;Rw$t#2cy)DK$KLUO z+sXXDU#g3j6aeb{B)nZ!5@Vptss})={H8qf;)kJ3i9Brx!=%L8*K){T z;r)r(;%Y~!^!iMN;2tz*;q;Ud#dD8QEi#!?_ydn@xORs#@fxeT1^=4MpE#XK zH&5u6a`VbW@7EdXhwjVY4>Q)WVvZB}1m4w$b|w0i5sg{C9>0eY`~<{sMN(W!8-_DC zx+Vp>(0cQlJRC1q{{|Fg>}6z2+yl5Mp}fsVmo;JBJk`f=b#hBYsiQ14!QIoY+iM(m z(5A>&H}i51wh2593nm(L8zE=74iC-H5>1gL zf4C_tgb;+@RXw=G`*`ONoJD*8{`~`#OmWCsy5@4BtHUdCXi8${@}`MT<|z5==>r-# z!QdYw#GQgfCQSIBa;bjixHo?$-P-=EyFomW{|{@se|g*)3jXUr)_-?9|6IyCdYQ#- zdpYNcf{N9%S4puf55yb*0stQ{cyN8BI-De*ynU2F&wuwyd}|-S;m%Lk=%Da3SID)8 zXQQXFusQePKqwaZJge1qEGt7?9v?QhEFR$=!#zv)rc%64&EM54g|9&f(x-$pPb)1f z_Eso!R%_LVeNH>h5D$Ok{5&RZVIk|SRUU9 zYdf3CQ5C}4&u%abHm0-CJY7F=qZzq5(_S4HpTOeH`nMQTJmR6l9SX`gmwiFjzJ~K5 zrK`*$ViHiGr*Z>ahM<{!#gVgOyJ{HDRzQ#nfk_=$@vddiT=M`AGK8!vD=Tx;b zKMGLl7MhWpU|gwe_k1WbeUQ>(nd1Y6%;gA7h&HEGF3G)QJ^S!!ra7{*VE#Mb4|~fy z4hk~>Nz#Lwdq7!lE7GlJA4Z4dCD#UN5!P6vgZQ>)<3T5WP;S_Y(&VnV#A=Tf)y7XY z+Ud#qep~zX1lRxC1yHhk#lKS>a)3=%qb}2Jw}KY=Qd=jqDI^s`p`Zo0@79Q@cyPDV zx08Wfc)X?G^W?d7q_T9Q}k$;II{GrJ%QvHRuUP!xtj&)=1FSqOA`j=FyRx~NhJ+wlB`XF$S2X7gdRYW6d&YDkc2xzkCzdj=z4xYX7s3<*70?_#fx7_Cj7` z!u8}pxPyopK7j4P4%Ku_K>JucYeRkhy}{9wwkXO z^=z9a^lk_nj=_uC(+{d^ZykD_RpakWEZGJhVmex9eK+D0rxT?YvQK(W38P-Hq?B%v zNA^2WX*!B0tNnll1X+&6#C*234RcoXTm4JjAW~82Dw8BbDEiSlbZJGFVU7$A^T=~H zn9Z{1Yh4vois)hhMOJeQw%~2?l3kYrtysX zRn4(Sa@vTS#<}0!5)ug&O>&kGeMM}zi}h^$=1F2`ahi^kd~osCkj=ywxo2ZDqz`>P z0QIT+3nSgXTtF8Tv})sgn+W2p-x)_E6A%IOCFVcM_;% zSMbl15^z`VFH~in5WAh@VJRQTG^_owaOTZ~$7uXWaM$EDnj7H0++f=UqY3G(!E|4- zqsAq^sj4OZzlqA58g*iLXXZwk- zEFG3XgqPsLP?2kHX;$RRmab9%fj>dP>n`WXJhWTpW`?G{+U{LhDJyK6sep7r;& zb8?)|w6H?uuYzR(s4M)uH@%esQuOvsu)Q^mWPjqTSj2L!=L-hWV4MZt4v8y0nZwSN zk+IpB>L<5#<`c=VlaXd1@#H}@u?9~R6NBCbwgUUHuEq46PEmw#Z6&@o^9+mo| zXTJ*n9^AN7om9p1Ls5T4;mf}Wpa1ng+W_eUhzRQL_*18c_p1HVSZ3-_i7c*eTe)j* zJAd5m1$zn@VFMmX2fh$hGWTphI35reR}b7<@t~%9ow;Z>*q;=m?uf{@vqT=u)A01p zJp}Sh{rcCXBf9IhGGM=~tg-#q{cow?_H`~l-4@X@+SjQSE;;w<`IjQo^B2#31>_>{ z?B`w8y1Hv^Xk^s$;g(j*or}T+*cVxYWf@zD=)@v+|J3^jEQtVFH^L9b?yACeFH&22W93Fa*G6-(7xEzm&Smm@XJ_I z<7lDKI&ii4o5lw<0y0A(X!RTkoki9O4)3%@(a;w|=Hod-dNw5 zMX2i>vw>eI2Aeo1C-2vVbo#FMYm3;4KIGp+d=8mSWFlo8Gfgs}KvzSrqDl~vTS6I( zH(ZBZm%3nr`@CWHzg+A$->LpE z>1Qp&>kwL>eN*#YNu>QgPY3p%h^%VMa`h-&Tt?IBJ~?^}vvQ$_ zG1`mI;I2tjy9acIj>MzC=u-<=a{=HVKKnRsS=B!3&9Q9Ra1kk9UW?_WlZ(V?1+~5t z;Z@bcKzf(^Hau97t-DBn*^HK85;iOG$Gj)j5^&wA}}a*aokg%UH{~ zsd;aI@bsEYEr56#Vn^&zU0PqogEWXOlZ zCnhUvR3{i`S!{>hEZDw>6ezb$(eH)M|EbnHAhJgy3w8M#88E7h=!praz}GrA4ns_* ztMNsz&-~^)+`|hV4>^TdZsoE1w>ot8R#3ofRv_lH3NEYiYQWST^QU|XHwqw11xM(0{<cwz|}Amzl-ZAw3($ir*9)(3`lW^k|%z7eJ>`O5JwjE$Qoc zgE}=P&0zPzY{>7&aweZ3sh#uJ{pAp&p<4$UiPDn`;jm4k1A-mpy|j=QzWGpp+Y1Et zCw+3NBsQmVtm%a^W;HY1YSb!|{w%<9)Yklv^rJhWZVum?woR|atGS_qS8k#-BI*SF zHwO{@@a=lFlQVfr5^!$&2OOIGd~voSWVPjIhe!5RBAN`b&5qeH@i|pJ(%Q*bkni-0!WXo%XfgWzj|sXfZMD_6@Ahp3U_pTcyi=PoC}poJec4`2Y+QBxUM++74B$=% zD%2*XX8@~4^k!ii$gP#s0*z`938VJNQdTcm>1O+NKu>bGQIDg&eYWSw82!fDy3eeP z_kv>9je}p+{^=dFAPv*7_;gQ6Mo-JNy!E%~rEG{^TN%&j(kM7QIxv1TefPU2#57$z z`ARzEVBO3`eW7gLj0+F=hSsxq$svIVFof1Ymj)=2g`x(xgF_?ZM!A5&0P28XtGRh+ zgf&{4-5DS|WM^7{HUd1vg9{-a&>rueFi1_i#7@2ta}o`pnp~$Q5LEhWC`p}2;(?@t z2+g_K*9ycW(O%Q5rzi4mnoIE`Ls5h={iUq;<3_CRXA6IZzWY3nsNoF5QDhd=!k1OP zQXaKdiKN^dJ({l4D7$Qgr;QL8;upUZIz>!GaBm;_Am75@9%xlb1iWt$vXY!d;sH3f z3_*{9&$*t|Sv?2pe5j}Hr|mAATF#Orpmny-?XHEJ-H?@%pK=~Y=PcqahE&_y+PXAI zw^7I6PPcwWlQe;tUN7{X zR(d8zqj9SP83Fzl#n0U|Msuvcy^mh`G7>A~a&}&J_HZ($=e6>6d8dBa}!E z%IsfO7Ft%1WBLc$YC07b08_5df*+(2H+MTAx32BRoL%bI-gTDli@q9p4d@)^VbFE) z^kzb|g3waXfNTFXZYSlByTX0%u5m9NcDWpeIzs%~Ngdq@2=7H@%mI7E)6(G8^!m-u z27*U{W@zmfU}|k5v@1b%U556@ARL^idaRV;duqn`1+?j^7CL^Sk+YokOX3XsxcfM8w}BdV_y5 zZWiGlC)t?)kYln*?S3}R)3Y)>>I59`D0y!*llP3b=52};Grwh(FTib@&tXzBm4kmX zGc6TNonJ%^eet`|s`6;va-q;EWeC1^ubyjXg5imnb0?tBBn8wKue&0o<`xc z-Ek{Zl9J-O)C9q>`>n4m%xN7pclh2;645`Z;VPXUykv*q;ahK7iDUerFImeQh!Hnk z%!`V>ToUX)`77FyJfWfP@MCj6QFJrr(3#Q?X ziT%FsPc~KmwM&TKW39o}VXM^!Q)`t7KmVgSeAA#y3H}bhdop38BKr6*sOCGIg^B9A zk=XkOLxD@`8B*zLSYismon1q1{g$Eaul!c}8|2^V*`5L9-%YA?Jn;&@NQBb-PvXPOr90mwK}$5oD8hAzp8Kak zB3l(PXO~X%M_umsC0geUyBxg0)4sEjiPAT}b_Gdz~E!mG@)xD~@i^1wc;fr{&#!7X&Let6>Q|MW*>s&}v zUfVCpcaaS*?q(G9E4oSz1MG~t#=^+{(H}sKFj5%-CSmdX`lnmQ>R%#$!5J~NO(lZ>euZSjr1* z*5QOG=Lu(mBC)T5_ye!K$5$XfqnaV>e(De{@cZ%oIwiiVURt@8+Qcys&pT7rb-fJi zMCE?Rd5Nt`ex4~HATtQ76K_!UW@&v00@cs%e43HL`|+;-cN-JutQN*E%P0Kg#Psmq zlZUI>vh)NzaJvt0Phww)zqhd~ckAM%kLUhkzQuSc@}v4+!vFL6qo%AcU?zagrqNC7 zOT8%q9WopATM}`~WpfYR@N=0;ES`xs@vMWYodDs>hgGfHk5ohHs;!FZq57$#%VYfR zOvl`a)~)8bko}iK^9dPUUk(@Esa7hNh!;*)Hn4>sYcdQm%hRh)EbXE6$n5EMe9N$8 zWaKBV+l5_!adLP_NK0b_%L_g17KCe_8Y&Q(DQ&Hc%_6TEA_0q;D87ju{-`LCx1~Mn zEoM@eD$BOS@4oh$07tx=_rP;Bv5Ygg2%fZneT_RA??xgvr3rz0jhJ=I=vL43S({0b zZKF|*p6_37*-yj>S4<#uLl1nl>b*KO-qa-pl)v6Pbi!8n0tBs)AgH*y&iumD>sfm= z_SA9@5eJK;v}x?kG;ib6Iw)IHREMaxxAE3$X20?kKe$Somwa-WrAi=g!R8{NfNN9! z=4^qEOY?`m5Vk`_ZXfeiM%9><@&FEzE#Aqu7fAx*s|Mke=WMlniNIxf-WpB|x!CIM zI-DJ)aM{3LIE(-$wvPIm-@5(A1?Rz?LG)R!-iPh2H=w5Fx7((dKNJQUbk0|`P#M(i z%+0st8FSe0sY#=itsF9-n>m^g6qD+re|b3wjBlgyW+=I)+Nk7<6@y}~FJwP(33WAR z9dWhsM4(J3C-?P|(RM&6eI+TpZfG9rfvZINAH_*3$?D1BwP<{9zC*OWOvTB{;ypEKEBc|8>q&u=|yKhk@Yjr7Nem6B4fhox11xZ8-}{uYnHw!slb@hEsIPX~gp7CLeeYg_M> z^3w)Yxj$E=vc@N`ME>|~A3WXRkExuuUo#m8)@1q~6=nXY+R_@e5$US!*t*$De$TOr z1C(Y4Co)1;N3fN7fsF@A>tW?TqtG)~h98$^!riZhZa#giPhWg=uzJEWSy}K1hU(o$ z9-Z={@Joj_C$Lz&*LEG=D;EI6%F;``|2Ka9Uv#5eF$)-1xz|Dv0+85OF&X4vsW0?G ze~-#ffBYiod$_9Cs^VQ9uR>(xR|#=fqK-Qk?!08TL-V-x*AidWxMo9tQD*&sILH1h zNO2aTez9A7z`XgTOm#2U*@_02Rx~HRYl}YLUe$L}J&p>-mY7sGZHCb1wuL6OqdwIP zGQyl1TU{WrnhS*Cv}s0yKZ^{7*OKXF-RUb}#Vi{A^A@&DJm4TWUwHXKr-HC|l4&{m zS(WG^No`<=1z;pjJo+5Yd+raX{IcWy_ zeo2#06PG4_wiwR8OqjX1u^R<3lHZK7G36TiU_3d2lqf+rK)O>(qXv$37lPXt)~n#+ z)Iaxy$a@!=;I&Bsgu1iYE-QjQ<;P&r6sdrtu`aDQH@xh=A;vM-CvxzT@P-3S3#$lMC<;NLk>!yUV z`60@zI}qsu4YSmYzoe*)@>ZNQDKM2e3QqS>vD2K`Y*S8p(3NuHlb>_;0+wyOYP5~ zG5nWmnuxb|Sgyvla#(=!LR zM$>9}cE&>z(vb`QG9>({I~$ix-*;`LvcR*k^_m=zZXK`0cNR_tbOddaSG~~Pu?IT-}sL#>A_S~1H z>eB3CgXR^MRgljchzX7BJA92200Y}!F6>fy-n~LIDMiMfjALJKSPoffbXzm1k9YVF zbq;N?5?m`cLE!i(zxXJ$GV6sKV&`nP2zu1;q?QQ=nIAY39G5GO7!HfRkqS0}+3*Z3 zLZWh}?3BXHpmi-x#U9zy;UNQ0t%d>P3}^|C5$2%$UxiX0X_&$LHuv2<_AWaE_2y<7 ztro6)*43Y{n36QHu??Gk)!A!D$r-OnRNedRH5}Ol2SGk@)(c&?Lx`k7LPilv8~zrh zCWQ|sDUsi&UgY!k?OlJ2uyN)v|5|?SVE@~;Gf>7ZZoIJH#2et{7VX974n`dv!Kp<(s!zpJwrcjj@um5nyW zO07?y^u~o4rINucpt26bYRftQe$IJ(?OS~Za~+$?@Zbu~OyPsgdZCHLp5B*+mo-oJe8WlK+>29IEz zVM1hbdbXD;nM_|l*3AV-ok%E6r5Ah~@5?402E%#qd>!Xir?*}+UD=I2yV7s)4~O?w zfN%MvHa8n20Q3p#+1;HazZ#KtKD$QlPgm=s%8n)az-F(GC93y5DBKW~u$kczPi?;C zf3R+igVC~Bf~srkKG{LMrBDFd`M1C2ZBv5K48Yp*>Xu3UCx8C3DBu!&GLD$_P47T~ z*fENTpxs-gg6@!sp%kvF8j-D=gj;A{z=s<={B9OQ?4A(hX;nZ50EF~BU*mc5+S9G} z{IYayG5k1IT&gydHHfjwM9A82s_m~}N4^bUneiT;amVmm-f<7>ji66ukBKBO9o}uW zQ&m@&xW`a!YL&$4r6&3?l;eW4N<3o{1Pu1@6?#c^5;dqZ)HhTp|1h^@>EmL`yvfMR z5L{(Ts2-S2#U9Rf0jxUBow9EFKFRwkDdR6`biv4ksUW73nBgyCBN89`NZzx#(x0Io zsJM_s`PQ9~{HwXMs&)No@0;BI3%J)qgdsa5qHo9wP&YbbDfA1Dl_LPhf+Ljz*Yo&U zSl8^;?4!flblrJ5zQd~#vqsPbJ=!WrUYt%^l5-r2u~!@pn0+H3o$t<^zD=7H<_4@6b<7Uzf6mgF0+d`*>r|W6lA$G4lkaORyYp=^X=_>hczPC$2DW9=L z&TUWGg>Jh?3;I-4UfPETElzV~8WB@d&8H%PYCSa4NwDAMuG;CCGoj4+)LjZ)Y2%R3 z#Wq`(Se3#l?_*tls!H#ASOqWgQFykdJ5d)Ul*j*omHWom99fcigX_A<8<>`gd4=_x z;q_PV6K>&j1(0M%&L#}xh%25PJ>Ca^g za6pfBhX&Np9=j&CTxw!}^_+)!^DtEVdP4Iri&&?P3+FsjL0;yaF3Mkd^}V?!T>VUv zDy`qM-#9mGCAJ1bI0fq&r?5{Q@XJhgDqe=V|L5+m9iNvc>e;#gP5>?#p!^2XAcl5>Vv*yV0 z{BwKXj_c3Y6WRj=}YD=`cW5OmeaT7H+e8mkjo zYrZL5p4uFlYjx_j`^j2kK}a?`mTEgfbW-IbHwRL~q=NcaF`)$j)tvM$mtWbzfo+&8 z4Uc*ggZ@(fRUP$jNh&MUM-?86mIZ#Ks{ePcw&93O5xt#ebz!OBc@@qdF*7F$wYOhw zHet?9=0Gr=j7m43J2+6Tn}zS-`j77{VlwHVmyL#~_LCu^N@ zi+O%C4EdT$SN?_|rt4irT{lv>J`KLfxamEww!PuTznPwox)apa!-LvLAtGJ`J4aS# zF|V#lXKpyWU5pB5iF@`&99;&jzYuI)&P*2rtHt|Emo4xZ-(t#(^r;xP|ABPbJ$Xec zKN$G=!~v}y?IR+?@I?exOT5daSX^UsiXd!}mKJz6T%9Y6~`tN-&a_KD^L(<_YY7X{K&aP_M zRUoisT%$r{Ee^gZ{28T9yiD!zy>mNs`)V6hzd0vSW$O`6lihCp?7*h@+>F{bLBSw( zM1@7yhz<|w3$7|?r}4{Ai<{Wj{2pslZ-%i=Yt;o6jh3^-Vfe$}Bl#26%0|MeWG_HTyuqp~o+_J;Gb!L#~e5(^Mzn*OsnQ-gdS#RhbpELKINQMi$@hyH&-?ISH z%$y{u^vVxGnfRd-O!!$=@;U(?{@tIU?KCAkWZ;M6Bx*ZCu4Y>?P0+VGP-cvi8BJzA zm}3#QD904;^-?9qT(>D?t8q0LzJHr`1VuH&xp6#btHFyH2tsKZb|0=Zd;Zet?PG06 zU7mg|0Y1p5qicLlwjX_RL6`XZH3j}b+TDx)#h>p;-C!H|`J^qpkvMi&TZ~;t!t3yK zN1OCjx9{dy*oLNsReyZO>(=cvA=(L%J0OSB<@dXgOH0&xGGO_!v|W&AS-c{-oD0Q8 zpZytdY>|iu00L)^8nLsR5v0x9;v>ijH40|O%7qB~qoZ_Eb6a5kpsJ#-_c2H1OE-s{ z8|FQ+ywct{7j-fA*?SE2AC6n(2%dP=(@F!>nI|&tX}tzwps{X3D<*F5>nR0zj@fQu zBRSYbOOk{3^ z?w&yC8U7YhX6Jg2&bg0_ayStkEk;OxRv>cP7+q!Cd~4d6L!=6OyqS&IVBaA$E=cWM zR3`~r(`Ex&vo=?LWBe_HNGW_Xc`SaUzmxi>)+CV!q#9L9?}>hxU!QxxhMq+;m~6LA z`|P_rMw#vKXf6B}HW1aXHNVJRRvl(d^ZIo4KW+qwcM0lQLYy7qZrg4`X#wp zq&M>DUBOqCW8M41MWGRCDaxJrCdj8sb0y~(z0;3(Yxvdm+5^J3X&!iPLE$NTah^Sn zs5R+UQt;43n|^al%JP(C?I6;|*it5Ncj}6og+GU7()}AK4S+Ntefb`e|MY4Oe4>Rb z2TChdVjBO$w4!kjwcpK6?|~Hl$<{lL<7Z*zp6+@UKl2NzJHIBCWt1RJd`#%tv&9Xc z#t>Ykt&FC=^dH1Gb>zaYlhe{sZLzD;Kk?49;mA0e;8k>Qmgjp~44&Sb<+ZDdX}l%$ z6Sx%gFI{HISm&Ps>l*nT*Y&4MC)bGm3jfizzEHdRPlF&U)FIyAZBAI5b5ajya|Gx~ zmE@Y9taN7A{>CUccAMt2#8;NP*QlK>o>y8+0@haJVb!OL+^E2mbv=2|_C*EpKp=F* zAb<+K0(u|P6=R?BeZQU`0Ji;`0Z!x)QQPeSf^LRR5fd7I>tkWD+S)u1gadx&6$bo@ zvA@&=S}e2mtxO#d3#4Rz8Zk4`( z)-v-2-q=6Z)0&4Q`RCMlp+J+>mzb|tr;43FkQjU;5mr2z(mKA8H}1;Td~RXT z6U`vb^8BSI^Uc?ZT9MfaP)$jZ{q_U`27w7;54Fc zwQUF)TWmWSs2wzs>Tp6)G`1$=+9xJY$r8W3h=aP^Nm|LU4l0@>|L7(tA^$#hJhQOGib? z*~}5))Zf4LaLWl5eV>tHbvEQ$2 zNs^Xiiw$y?p84oyl&O5QHxSKJycf|`!8E`&$@GDtPFXp;erXgo&HFixR41958_u{P z`fwO9A{8->{_SJU{b&WDf8;}% zzHS9z4^?KB>Hlp3dcqb+L?(CaqnVP$+-6*jZP4S5ZDDEf_pebEQz=sHhiZ897 z5Bb*CCx2`RZhqmDV*)umDZ_|C%FUa7TF)0To~z{=GyhfM;@9E8*7ZIr4KodNGZ=I9 z+>j`DnJmt*NI_zX$lRlQAlg(b3T%t+ry2|1_0rF8acC z&-ywk2-yy4W*Z%0#@0^K~K zfAYN$I=^xYes<$^wg1N#W7C)C2ho8p>;Z`)K(r3+eF}6$|7wO93>9h%r zCy6IS*hTM%@ze5APaGyWuD0*9pdUD2qAX*SY02Ul78{Sjxl*SzZiLZoq-n>Rn;O@& zT$#^|SmbGg%CQ3o`cAT1I|Zb^&?IyN`))ZTD3>__kJ_cl!{~k6cs=@IwT(Ir8q2aW zT)&Js3{DWh)3VYp0egk<)A&WXnKiXH#uxu7{sKV3vHLz}JLh_it}Q$NC!VGQdrpK` z*>-6y>D)ah-t}-G0`X|(qXrWTF68`()R(+RrH&}yy*~j{i`hXo=h}RG-Dpc+>>Dj_#-fE^BLovy$2s-`0U+L(0xA7 z;8trzlfx-8RBrccYzh;i4H7QMgQjXG4E8sY#HCQPmElIOCpng!Xi7HCjtt@8y2yaS z$^~1*F6qw1ozGHCW>>RHw*-TD%atz86gyE@R*$daE2H6Lll`^{N zfW(esbb_dj9CVh2c{EO}ET!Fw=aV8qK?sD#! z!-wJM3Wm9X16|RSHmn*-nQb<&77Nl}XgcG^9xffb*y8=)1dZUG&xFW_T&p4(o7CC? zhFMi3kEBzYVARE}u$q3_NA3TB(&zW-*SMXPk$E=oHQOq(BXb6>f`^xeM} zNIyyoAU(F2LUuq=kX8~e#QTFJ$ZuklvX;-SlzjU4UOOB*_NHSVr(v%;OnaNN9zlJP z5wzROHG2cBHCv5W*XRQe$+iwe+G~NmUgv1GKW6lW4^N~Z8Q(CbL@3)aEj>tomYb0) z^n=gxxj@hzu;e7>#ijNBi}Wj&ThF*a8V*v6;Thbdyg!diV4Ysu>)bHg(rxe&qnQ_m%81U3VAu_$Wt{*-!2G1?Eth&=P|P z`pJmNxKQyn?0I{hacH8XRoipLchWVI&ph4~XHy?z`5jfLsPL#GP`{Yx1wfR2YFqX-NDCNXN2YK!q4ww;p8uOo!A^}m0@ ze+_3n-o02QEW0o_(NWTI01#sOer2|Ik3S`JT}j<>yz_-1+_Y=|=7Pjfz%eg)@m^%b zlII3+ovA!I`nZ{xJsHn^>hZ^zU`;t0n-fg%l65LLs4Dq&Y%HD+koL3$+%Y*6ngeui zcntn3G{;r&v$R$BQYFW{d|MSc(#EU#=XXQ%CvjI4#`zw)w*UDwCMK#Ih=X#6Zr0)zGf6gc zSVvGDn|^RuWVo`jeRXn{Cv`K}hUFv6=h{7zXolTF);s&tjk^vr1t&En4~$%^E2|1~M)YDOzvyKDGjw=}bn zu_7W!c%f3>4pOa0&w!o{T-iJY&Kk(tLijQR%liFy795BAm7WEs(?V)i$Fjhh(U6-q z>n^R{v!X(2%vD(2byvL_$rSCt)i`WQ;Nhp_G~UK~3a1BYx_(@WCx=MRrte4B*`LJ- zO7QGN0+o7(m3_Ld&50Op=Lm|soBhHHO2_`ui9CGs+paFf_++brT*VbEje3;{)h}C8 zp`1mmkGloV`{Y-&Wt-5~R@Hgd^i*AznAhGuu0mw_9Wh$Hxj*!dz10=-6#=Vzwq0s7 z7X1nAA8e&Hgwch8H(REQW>Ub048Qx@SbvzP&U_w2!`5g$fQ>hsox>B84Wj;q5P`qS z1sO06^1)H!%$t#;Rrky{L&cC@&}BEgfrXVCIoOyfjq0vyQ0BNf)H?Mb5|2`)6&zgI zue_vgpyRCJa1bw8NEw@4==ocLA+25QYrYlEx)?HM-!N66D?PqM@96}V|J&-uPQs@M zz|PsM*V^xe%|C+MxBqKm3O?x%y7nJ~QQtp7Cihap$q=a{I|T4g9_82ToM>?J=J;XnvJ8P#2V%Ba?l2NqE$JBrk+(KV3S9GNNd1 z6v)UOoV^)t6k6mQ6U7wxuwkUk$hVd8o8UPP9Y!{W-yT@A0l2n;C`{1L-A29VrY5o` zR_fad&MyCugKq>`8Xh`k2PJ@~eWdrGkor0OfX&@v>vBZs++)6wF&xLMTuzUyvmw*z z+xDb|uXQ;W&z64Pr&3C>zLKGYyTm6YEOJj{#X~HnvG;6AhWl95N$Kf&ni^%>=s9xz z+aBlj2VG-A@;^61eLS6A(~oBGp2#7C<_vh=TMkBp|(oDxE+86#*&IrB~@Cl+Z~~ii8rRL+D)~bV3P% zS-$tZckawucjnvq^n7~OIsdcw{_Qg$$aV~TI+7gy783$LC!L3j-r!oIFA!sCwY?hc z6)Eba#Q{vcTwg`Hc?dQXE67dqo)wV%2|5fxbP&dl>+vZ)SNt$Bp6cmL{08qw*Q<~) z@(>?2sA{%f(7V}UrKyCsZDsTJA?H4WtxbsUo}ZT8FJljbGp?2|t`udjR9o+X-H9ui zUc>@zfNLPVb?dHg&xYyl&FIq?fz!MEF_$<0LvX4y?}%Lf&j{wtf76%$#4uI3yMOvD z`))|#CtD3vAxVX-#vPDx8>G~1%H}PgQD5nRgoeDbZ%a(0zK8i1M zK4reY{ec0Qnuw&6$Ev2hd7mO|;=;!noEP@Htg?OlWh|$QU9_~8+JuA4tZd-vwHB9y z2O&K{9ELmMYE%ca9*48|gzO9M)ex0l0k^(pB7vT9&-9PBTSsUUx~X~iaMZ95%nD2G z3#)gD;?7!+?z%VmPGIx5;k*t))*DdXtgQ%R+aifL%b3srqWD!onIrZXPqc0+$BEt2zns$IywM1qyUUZ~8{4K}pMCYio$h8;n@8)|FBz=J2Z!%J z*3KsxG#h5;YEwkOji{`^rP#lQ26h~aTYwYhe0FM(3dcoc7#%uw4RwcxY1@F^$3n>> zp4D2FmY6@L{Jx;VietFRcjwCOu@ltp^+gb|?46PT}xdwkTg_q zQ%pTmpQ9Po%=5nAO;Rq`5YQ@w*cyG8IO;%vUH&wA8cpwN^vj6YM(X<%o0H83w0P|Nx+5^*Sw=8bQu!Y;q{WVXz2TfoJcB8pGp|)bki%_9QLPGvU7Zs&OY`NnIImL1z zFNO^3!`bGdnQ9XpO?5vt_IjqyH{e51lHdYmqO~+*{Ujj&-kKupyAXJa#V;f(qvKnw zmDskQi^0Q7Sdo&g#d22)NKD1MN%&i^Ez);`61`54mR&%FwLy8!J->>W)C`3PSMRTk zU=lohRVlL))1S(pZ0qS>DDZ#$V>y2X@5z4GvV#X3QO%1xhhf!WX*lK z1y=#L+PAlzUew|zxq>oBYf34#>*247WS`4}JAZfhk^FqDzY5iTk&iOC1a*a}0!!uP z2Kg=Z0>_yQ2Vp)_5GTJJ!9AAhEu22U94RjeGu$5#iF1i4t<01-EI}H~6OK z+%aE{v{q8wQ>;iHn+H=eB2lK(MmGIT`6M-2yA65I(1-r!lsr$RxB#&vLoSP%xO^H@ zSF~mTFS%Du0Ukd=_%l*8ogrO2W6OT6zg?~H5vQDeYV;k6>5zlXW|>&2QtRC-fyI&& zlS^h{u%(mi$p#=~xs`MM_-Pdqi`mk-x=m@tK6BLFK}WqHC*PO!`9uJCGnO{kQbq0_ z=NV$_se)zTzuViim`m6GjeiCA-J(+>yRILPuWPBsF^z^wIwO~lAi5-YWWmAdzHzBo%NafZM)pRR4l_L z&*xh5yh%+!$SGOWJz(Pzl;T65pFcLlhGd8AR>%jGzH?-)zf_sJPCAf`<7u--ovOus z1Gk#56r<9=n2!2~ZgLO!piDSt$?jn|1K_mma-E!~gR}TihFAyWN})y*%y0XwoqmcX zM$Pe$sY~N9b1~<7G*WlGo7DNdOb<7RGE5&Y`lH{WG2H0kkAztyt=ZDkz&A(nG(bf>(N&M!L*&!Pu1GhP3e*AL)C%9x*yXJbogHY9111F{_E zRdv6l9KAw}Rkfc>35>4?AVEzY-%{$|NWHwStGOWJbpd}PHrrqQl5l*WR7EmTDuKE!<061pNy?mF=fQpzeAj)&?1Ktw7#tkxKe_D9Z1I57 zIoK58Tv8UYP7=~5SpG&$9mVcwZsE$wpuL#4pmH-ZbmS12KeO5f6Q{OHYzIhDe*Ks> z(Q$XYdnH>0m4W5h>cGQAUh2GYd57^-zchrEEv#||1S^%!jIf`Ad{)WQWqoXQ#Yod= zxNuf6vIBE1Jp|{o$V6;|nb+;2z;>lkbK;UR;rJ)L%xRYI6s=*YTz_oc>M6)I`{{}s z_T(pJBhd{}OHlyqg`c$($G4ovB3DZkN}qc7jiw(o#T$Cvr$`LHg-jQP}z-~2vPq6-sA3t4vl(G4s%-|2@qJ6Db; z!1X4fJFq!}vShw%W`+)=l(cY>_j(kiR!b>;4Oul?vF&Pnh21{jqz5ZV@%+E?M7P3DBhMbMF1u4zy>xF34mkinR z0_%Kcq3K?Kk{4`yD6ef+%I|3ye0K&2s+xtMemxC%&=P#X3caqd8G^;ozY-d_S&_GGTa3b zEFvEFCYG^8ZGs&We#V@}uU}*e%5E2`vzSCV=hZ$MKitjxV!$5HR6kk|93Lgwd;JC0 zI_Z^fKX?{D%W1Oz3Nfv#q5e>_T%CN9qcT2aqN52`gh(i_CJzpH?_=DL(D?(@hzRif z%94U<+4KaolzEPguZ;49KZ4sTx&&yrfc24ru2Nmz6+h4JjYqP&r766;0@T&WIj*!r z3DU0$Eh`yM~nUb{(-=T66@DO!B17W?6ZQS`Q^4*-K4bz5Yw$`*g1B z|Ct5oIA4Al34Tj4q>1$zfxm#pzm-~L#%S1#|2fD#q`Rp4LJF&2B$kqQlAVyP{9;vaABE!2=uMu)`drH}Xr{A1 z{={C@mr_x~5TiKPovGNN(6}3b)i3%+V(x>3;1^8m20S{UYb|ns_LRd+3f;$ z_Jdly50ZdUQ0-CM&fqzM>3fujAu3U@*i77Y|y2nGuat)QI z8fxarD$%sQUdOe;$(tc)Mw`mA&|_8`EkV=Oc5>Thkax{HTdu5dRsj9AF@;ANd=yhJ zWraRDkivW-00L(pNPd{@7H~`k4fd(`-$}nyUQ>h46@(=sD7HyGJh!1X@*bSln^ZG+ zy9PJrZLxFut=tzBZhEocP`I?KI5h~ZHqS4hT=B)xDDJII!N8>Amc{Oy{^Ho@Rz^8A zFI&>&R=s(99!oK5OQ9FeA`Q6O`|!U_jy2h{;-Eei=YlrHNw-ob4XNem<1v9m$*Yq)j(acyx48-8LmDv?%~m_o}Xy%49~CizqRk-IN>pRPIp^;l2^0!7h*Q3?&r8G^iUDk z?m7<%*f~~cIfzs*PdK>gdhu&7W}S+~%r^LPgo{Jm|1SA$qY0W%RD&c&j~CP(dkdOh z+?4U!R5#>X5>ZVJ{ z(*lkK4+Vi|yqdR{(GH{IEj#T+A_;1&g_6|fiJ13to9On**olF~vYh5H)e?vLhm5^2 zm(4Y=d$CpMbjysL@9q|_MXiL>KscILy}&Jc{?Oor)gGm+9`W8y`!pu zB)DtfZs+IY*`@UJ(m8=EH^C}WGb2j%l5$C0WsR=pW{M}Jr!XM!kD?2GMdAQIw1sA2 z?Gc~2X6vMss1~S-#b)o|k6Gh%KoO`q0?U-NRETClVtSF~6=0*j<-~ zVRvU}WI6E0`p|C)P+sY7{u7t>c8)Lr^ef z)WpqfMRdEz0UV)F_zMz_^4BwMnFjl<(i&-kp9Zz!8s;zY4ahd<1YUC?w&h0wiyw`) z=K^+X-IoUuB%}lvKwQzA_OYP7pOo8sKV$S27WC#U$#LF&(>+mQ?Y4GQf-Utm0QPE^ zB&BayYMPxU15tg=KHxbls90mG@J=SuqEbX#VL{RjG$}%gHJ%9J%F#b|zSU38I1&rX zfEf>p@IOyDb~oC>2Im|nRJaWislQmwvkI=WH>0{Qlt5|9&YwC}xqM37RGWfQUbV^o zNuzlytBnefF$R;pe&7~SWwB6fc08~Cw-(E z9HK04SV(EQDcNX%{}sQ$pH;|KQ!vwGS3X3UBMH!>j^HmfzYVVKqI9II zmx|mf#fFF8vo;q^Ze-PZ{5YP3Q0Dcf>0^^+*8sUNCWvZ#M2l!5CHl&*qH%Pr;sAPd zlZ;a#uz>c?lV2y#K^`%d=PzWf`5N}#rq}v@^D@MC1@f;wf5;VirrjTYS%0S8DYkSH z><%p%84SQ_nXAX}c3qd9Q7CGru2Z6FXr#h% zyhf@x*rK8%gwNvf)I3ncl$K>a8JHZai-jwoQa;_Y1&ka?2F|tD)M(Nv$w-7mslLZ-%^R8ITNgH0DAU-6GB`b6D;d5JIU%RGQq97q0&@drk-z%_=J(PW$y>4SPnBKPX2 z!H;vs%bqoTQJbphW>Oa(v>UAYY7>Ai z<3Q36=YH+U{;b-0|NQSQlCyKS&}aAz9tM0m-^7UdL-+mj^Uk~fpXtk$gVLi}81<`r z-`#h~K|AW0%wFZm~>KesG6eA4%9;OP8?`m!T7Xq11I7qn^tSuIVX>mO9G z%YYs&bG@+;2B~T)skz=^8=uS#=X7kC^C*kHE!|n!bj}?9&MuQ^qpZE!D5B(+zU2XK z@SU>=cq&KZ7W9`eg*43D7lwW*mN22<;e~yfK?Z(;99)oll35dcE6u`FfZqT=&q9&v zPRz1$n%=!7pb`c(P5nN3GIwIzPqoz=2*~vqEsN!TdaXDt;{fD3r6^WrvI5O3QhK~g zsYbgkXp%HRQUGv8QwpyNpf!_jKcy@n0|QNa31~@@p8SUCIZZClcCp~)fnD ztV_k})H^~J##S8VfBP3T43E)Kl${@}mYL$xQ$+tJm8bwS7+KEQhJawUmU@PU-y!J1 z^k%B8d>1jHvOVJO%f$IuPqA7=AqKWfHRJf@Mja2AIF!!D!)_{zoS1=LkM<>X>5a23R$XW zyJLe;&pEb-cLd&yUK8l?HWciUySqm9Q0wzN&A+3WtS37^BT6uX4c6)T|NYS((yh1y zp2icNe+t-AxsUbeQLAj$-1P)&hwEJu6`#f!(>IpcCB|G{UtRfzF`1XgQpX&}A{ru~ z^i)nR#r198*x9v#bdb^*CtYV{JDwM7Gx3$}nFS#88Qk~xBiXeLE9do0pOmEiXDx?= z*zL{)&HDSXa&H$-pGTZAJ>0q$h+Q&%DtB|UPqbw)D{#p@JOrhF&^|nl>Ww^@bLnU? zZt~RG18&3WVDbyarq5}rE6m_Om`m8Bfn9*6cuska+j)T+f?BmT9tWqAep%Dyk~YD| zx}oFL-+}6$niK6risBd=Gmf`{Fk=IQika@PTa$f)TFzx-7+BB^X$8tX9=7#Fy9r2K z??_qmw$B0|Zb2(}ZnbGW%PUXFu*42nDZo;>9^Qp!-7DJ_5-PI}p}RxL>J?6D&!`OB`CZEcbrma$j+Ul@143lQ6t zfH?xZ*fP3nngPB1@DSAKRPK|wv81UL3QZ~Z2SerUc`~Epf<0cj6n4QY6JA2L@^UHS z)OHnpmmBd^sXksqXm4M0Fxa6lW$cvpnv#_;T#u+rXA|C2`5ElmW=$3SDANlb-n}&C zYOEat*}V4jJGlJk05y_8yl)8pZAwH85)`4qsGM9$%c!s9WQMGa^xTqA34yj==?o9{ zgcSerr9!%><-oJ~+q+Wm{WGpCWS+wB-LU(_Wj`=GpL<3tLkt6kBtzD!efh~;(ID%- z{nc;Q{m+;G=(=b3^uJI(*eogCU86QqC6UH43|6k8SXI%dOE zHokFd5TSJP{-tt`rE;j^j!>t@CPkXSQ&G3YMLOo4{kGH=ynudmVGQq?O35==s@v{5>~p?{6^Lcce5PnxuB@t)j}G{w5e$}(US?=e?(hxU zBmJS$X0&Lk`1sfaN6o2ooyU1)lY4YD2SFlT@|cJ6E#RRMJa3cH&J#?vB10@jmBvT zdQRt9;$j0H<+FQ0Jfo#JuWCVo6GqF7%^B{tlRiy(6%u)85|Tu2KoYvmut2rq-Q`O1 zoa35R!u6pCu~jJUzMMT?3KQH8(QMTxr!>{mtckYKRJkevrF+U7!>6Hvl}8`t{};Tt@_)I5KjTNWS1 zHj9B6;l(@kOn8;1O{YR@^~!iqbtQ!YX<3Qb))UE6_P6v(8iTV1X5CrMp6J)Y3$zzJ zwv|uDv$4ufpmr_7i`8_-!QPL6p8faXWLv*o_1Ips;@qSJ`iY-N%MI!?#?s?OhBWQHy`^vc6MCM!y2yUnE7iYxoP4u38g(7HzGnQ7tN7_`h3 zBewYV10Dv6b?&bv zbpt;EV`90#`Y$4yuI*>M{-dSz>82vK&DOx-oa!sg6!_+&nr<9R&Js+VikcYga{RU! ztV2yWZ;u{u4H~ln)za?F&nxRC08IEyrYxNTh_rgnEgXpHg$W}pTh~&f71EM`3x;uc zjoRV%d$McV@N>^|giL6C*xhA0{SMd0C!4H#{CDQcZ!pvekD zqWY323TDdQlXplNy#sP_pz?r_`frczPHUJ}S3k;o24v07yf07DukUSU9im#ur?=p` zI2dJ-;}XW2z&*aXvK88Xyfo;$HNEKa+Z6;V^ZMgiQRDvI{A&XX)&W&;GMk6YT`6bW zHs$Zz%%Gp>D8t7-V%_*fYX5m@DxeIH+e-;V0sBnI(;%Evc7uBAej(|ASKQ)QKuz9^ zji3HVCym?dVEmVQ6|l+l^@T4IkEIOurjsf^$|UC};d6x{J;u2(O*KE^uL%c}kj8qb z#{qMLj_)_X8oy@*jr$JIkec7ER3rAISV&ItfE&|T1*ukenS)~Go{xBXVq={wG;~75 zSe6uIK#>f1MtT&2<@cT)HgV?_WtAz)7);Dg2gIwfh)2_&`J1>*sJVkpOiB*EIvFFz zrauV{*qBG(X$xmu-wIsF5vY42zkpaI-L5mNX#JzMra zjn!8&Q+S+kJ?(tiN7t-I6gdtn5T(3RE7JXB7a6J2ra$kQA}XeUmFp==MRs3EWIvbe zIdnbR-I)K4lpVY!h1@a{pmgIM+TUiV`>Z^|XL8!}Ac8Y9zNDgWfdj@0Edw>@c2bxUZ0acDX!qHt%&|t+(gO~6UQxi5vsfmo#e+os;hUxi zQb?kH7nRI#BmZtfq(oOHy&ndyeb1hbyRfx)SlWxsf)DMCS7)m*tN)Q(QdQP`aznVP zs>;W!f%F|z6AFLoeJXUVFU%^74Okubl1ihEV?~gnu4p1NRj@ng4e9cj0>8fwfPul| z2pIPGR4aKF*zz_Q1q(qquBuf%J}wZZLh-dYca!3&0N*u_qTeqohxVXmz@=fNE>Nw0 zem1LHSk;gW;h%c;Z^=K05QPkdQ_?QQf`muME34~|=#Nu^NGY&}rVy*KP1hAWQNC>V zTsaES{7`V4f4xYOO1&4(CX;C-RSE)L_NcR~TVH#E`FzPvJe!@)mgR?GO@dn^{~ske z)x9d*3GI0cl`!YNo-%qGgDS;C#RW+2-Z7t2Mwzc)X1VU;A+PUAA+EXSUOa^@KfZfi zw0U;ax(ZwEX+fX7kVdP=MTgOfbOFnIL1UrC5u%={V;7(xNvDv;cf2dRw#W{hT zA~4C@#Ez6e@8(A7?BrbDaPvMQp5w^6Yy&jj?m>yhYKvhPbmM~joy#wdRqAo7oPPbH z$fG66E>Z8cIu`K?-OabC=}?tJU6*+mV2poUc7rSOl8%YQ4JFIiAe89jrF0cSM;8L4 z0|dN!Sk8`6!jS8-oG?|-u9I>hCcbOc{&8(}Y$IEM^++2D6ErNIbhM4q>xA*ztQ}2! z7w~cWSZ1(QI9M=1IO13UG?tbM&fZ=y9Gax)lWfx7X#SzM1t8JsSPQHb=y5H5jAE_s z4N4djzwuUkXp7QVLrTFq$rBwxu4jPDvHDQ=}R?tSa>H7kY+NEl0Xqx1m%5teaJds8y&%C%=pX$4${O!4Uswt`1VS5K*vQB{znwXxbS@ZAdRPz|9d8- zAm1Jyi`%fsVq;6D!h7hwNU&6^CK&{5bmV)x*|W#~x4`L~$<2+rk*pe+sBLer8 z!2+%LLtMh8!vAifxXrbEabvybuY6OS%HMqrd%oLTTj;m3cpZ+(Y!5_%wEqHuQ#p`9+iYf@DaMsSp$}M1wz&Rue}g# zS27y?zS65g+@iKhitz&cJX*}yWyUV~kA0+v|9Ba#!3I!pz(@dRVN2zrgOZbe(9K=7 zcepU$YOMuvX_wxqj94Fl%rQt0=8IR)>{Wh4XpT3|h7+ynMT~`$B;aqx=T}rTnTM1N zr>~)Q@nh4-6Ojfct!2t_Off>ou1FHS2W_iTm)j~V7O5)UQ}|f}bLpm8YDkuAjTDli z%xN6-o_0~MKr9BFrwjGV(|h>1vTPl*9&t`Bkq9rf7x~pWG z$97xJ=&@D0(99wE5>W0jVlzKWzR&qovgN_nc4N@YJB1q)nB{XnGsW1gb$6m%Wj6Bh z+IlWv?sVc=YwZ8HnJ&z8hGe7+CN-Z4#v|XHdC`>QmXSkQS(t&2BedJE7yDEuuR|F` zG}S_Ul0A<37Q9Im4miz&|Ze0)363$<33> za*w^9NS6>$ao?Y8z)Q5UoKEMk>dbKKhKLK-^~o_GfZpbgqlE~`wzauZ_oLOvF8qmu zC@cNyO0Zq_%;&}M*CefzbPJ=or~b-z0v6=vMBn{6El#X0WdYqFlaSyFzI$^QrQ<3C zkZ%gqJJCeHrF+O&nTTa-c>O0mCfMVp4_>l3QKs1tmFfMS+!-!nL_?#{Pznao(6}w| zuKp1%PTygFZAFO~n1t3sEkAHbS+ICLfh>!&84D|2pCr#Y+zUh%zlZj}hSEG$1Hqb2 zKpCiDJ~1oZSiYQD?~$(OsDh4b1k0PcNPpH?m`D-k;D9UvlG@0`fV#nt;XUrid=3+%RLp~%QSmO-}cQ6gR=B} zqU^?BJd79_?rHIT~r#TWBd^I=(9^Fc>C@zV@Ua z-zk^!K4IEWDd`v%amdoI*FNKL&Ozn(#U-Cxv1UY7B_ zkfT!WXuZmgvC(*Q&Epbz6G|25=g-?*e=b_JOXoMjflQA}EjAOCAwCvDLk8~dLYA12 zD3vGZ73*x;)IyN4*eZvinSR#wWRiktTBZFTqNarW7=R->ZnUoE`#2)v+xme>OoN#Z znzRm|F%ZdAJvCPMHtV*{@spgaMrp=1HxUo~0qfQ<7so|&USoI3UuO9JX5qIItA|2n1u3rrUw(<80i-^)-qYaXp>W}ej{G+BgASKKd}4LOu%B+_ z_?Hy08k}Cyh<+x0cHLehoh0f{Pv

    $KvwXc)f7x=Ea585;1=+a{Suqkb-ft=W~+f zIi{oxAgmrzq zH|a^y;`pcxM$?!DDqgs1AfrTK%uMe z;4E;ses(73nP{qF53`6#!38q(cUdw|5*$5YK0a9t(_tcA=XV8mI(Wo0HIFuhkER29 z%zW_ahYPm#@&q3?yMvxhG16Bq!@soCuFIX8d0H zg`xl`gB8vTNn62n)tG4OE--0N7a%-@91}apKWLsgk*~||R&VkxL{3X8o9e>_ibQtd zU7`$(cCwY_W0%GhTad(=%Ig#_gg%w))j@4sQHv_{n;3`DrP0h| z<4?W}df}IyWD6CT$3s5HKJJeJZ8=mQYa4E!#jCfrR_fwqjiz1Ya)@e4LQSuGrrBKI zG)Q~eF`eZyJlU;Cr!9USq4Wsx`{yUfBDU8raXv$8e%$AE&#McCgT+E3ob^kOPPRP; zaqUHL%(85EgN9?^Ze2bjs#iu}cIxY{8G%%H_pto~PHv!&eUGt2&zjJZs655(r56fzT#n;g(W%-=sv6ip0?*YR}knNn-;qo5}BhgVX>9Zut_rMnr07Wg19{74#5 z`qP<{jd_Mm5jv8G@_pm##~RQ__8967go5Fu87WwYI$)N=-s+FYFWe0fk-E>R_Y%ZZ zX&lhPi1s?Ts4+t$&5Yl()WulA{0kJSGRC`7H>Dmv^`)Hj5h^cBpl(X>xVbDsPu8v3 z{1)w*7Qx=t8`)AjzcG|WX#&+aw#)tFI%qA9mnml`KC!BDir|X68a-QvR2nU(4%HU4 z92h6C$S5Bh9)GnxF5_jK{Md7KHGV0%y8rl}#>)-lK0)N~O3FlOHzg=!CBd;>q8@T9 znb&e3>OTDW^!)}sMA0fgxN|>2RIqdZW{)cN?B3sg^QXbx7kAhGX(hDkr@z(di2TLz z_sIsA?}uS>M5i#sBm>{a!W|j09E}dY%t_wQQO%D_e3jo9+kSjs1NAh#@CVP5y#;ZY z1!hB%A76N3ZBY=zd0TR~+-(iC8IJk1@B5=pNUf(P44w4DFWbXt^|8@~w>tHLq;Wa! z{X1y|Rh@MV)ysT3+#BKqRUj&=^NwuASjzdj_h4qBnlRI^F}8(UZa$ENO9^I7DC&EJ6T7c&SphJEn{O%w=q z-{R;w*Yy0L%obw_b4dJmxq4df^~{qgt>AM~N}n>aQGX_J_#19!f|ZdNwRMFt{E6}l zk%`d{^*I04=89LzD4@FBr1`u8sq>#2o^~y6uvUjD_dQ2-=di6rK4!L!E_LSVoRH_x zR-ZDnF0LfrCTkrF1mjr<$CJDlFUMLeDpTASU>)s>`f1WdPKI{8uTlO+aoSl&U=1O(F_Su27&609< zF5OJQVosa(hn9Or*a7!SwMVh{ ze#y-$n>6T}ZQcD^mC`!49ebJWNm@(a;Ird4qFlqZySb2Z`HPlvwz*H??Ts}5bN8GB zf2`B|Q9^UG3{oJBjR!Eba+foQeGK4ac`;m8HQlV)yLN6af8`lGsEKv938UOH)`M=e zR9+-EXFj}Bcy%NNt|gb4;nv|NE}wg2;YU^7isSP~gW3Cp`}5X}NaWHf^n?=$pGxsyc$L>^?+XI(K!(iww(y4jq@vHx zcqOCv4G;?F6hIA?dhtq#(2|f2ekKJm;?}B;W@7Wt@v&WH$dNG;l2hdtK3=l z9tK#!91z6S0KgL^dU2Tmd^+7%!Uqvg$uRuaC>|y4iQL0Go23M(}|5$af!PT4XXZ(3=5YwiJTurhj}q zB)*K$jHKH8wpuziQCe22uPN}!q;FU1wfFC!pLF6Ts}P+Qq@ax(ANK)L{L-yDYyiCOLi62FmGa2oB*yJxc*g-H8LTUJyiV;y1d6Rq#*gxR;wYpgSSJ1#AK7)`pB#Z zNLTzCbj%NnuLuo+!-P<@ZsEHmF(9>;x5T(rgttXP1=Akn<~I2SFq8y2;P2waRGpO` zZ`sHsWN!pa;JV#sux~E!v&1UlmMi|Do1~okWe`d6Q#Mz%o@`U`h9}dA{Fl;l5T+-d zedZk^qT395OELZvOvN98PfEagm8MEyVgBg=0X#a^8laxy7h8w|keDlZBu!&m!Kq~GwmiVVdZvxtH1Nv+3PolP`=6La@6 zXE^=7>$h#&EufTx_-*=Zxl`7EjD@XVKQP%HGcxzKc*}FVAFo0a->iqKcSVMbn|t+( z$4XLU=xX9gMm680rt?+rB#qU%$_g0&De4S;Bq;=*CAW=uy`z=I*6^7WHJlrXP!04H zt`4QB^bppj6V47fd@sM9MzUE>6ZhV$E%q^0G4POMCVtBZ6BMSZ6KqsS4c2w_ASY#+ z{lQvT9@b@zq&*V8e;HcAPB4CSqV&~l@_se!7?zM!yIDmfF(+9n zp)E-JP8Vr_Fwv4?&atE@FOvI(^4)yhLeSto(sHgbaAoWpy(^T~W>#DYANWphRahRr zp3Cb~ebPntE`jFRyZynZTR$r-?Dj!M9?V;M-74FCO}VJPpYR3dIsWEe`f^`imz7aw zC5X#(@1~PWUJlVTF@e=agpXu80*{uWyb+MB8bY)1-4(8}`7HZ8$E_Dy+^NtvP@Ke; zpz#I9jO#3TJCh1#W8hV(g*lWPIwJe^;PWkVvTTMIai5i*+_C%mfG#3!u`B#_CrcL} zFUc`aXv7^WMuv62th|>44Ej$5!+^Bcp3EN2fDAxmhXiCW&TDJNw4t<&t(xsA3%0cR zB+C@E9KYm|cIeZx8C1+P~dT z$-O*fm$l=5?RMaKEx2wX@GKFql^exu$aV3HuQWLD1c_+lI=xc`t?^%PnV0f?*vxfy zQbON`AuPeg2!zXqc4GwVbUWqnh1<@^V5w;Ph89%RwdsOmY`y(xOsD5CpUc6)#LByK6onrDcmdXKv*G)-5#>m5^&^tuqwVj942 zWierdKpE^+snG@acxhc83w=M$s>S6MJa2wTVB$$uY{et7Ebq2^dZ0TjbRNtMqo4>$gOiZVyABf*p5mzjsG84|# z0Y*tsljUD~$?^G4YA{T&JeR`*`yxN@P=ouN<743+$n8Hd6(W~S^p)njTNtYe<=Jr~ z`HNroy`mcxa?;026Rh1^?k2W}YFGA@Wee}{@bTt+7;DNkmPi~qq}VsUzvUN%KR)&i zn7)2{Mv%rv*oR~dCFeLdn9gV4>XONrphs&OQ1CK~f0A6T08?uyiotx7*FsN#1s<%M zCOH?DCMLtI982OA*=dYF$?wey?Y`&KVYn?JeB<#UMPr)a62Lpxzjgo9|DxHfznX9y zaJ`L^M(M^tL0Y9_C?7>dy1N73)5^{e5QO8Ri&{Z^lEBq%?Q0Cvvs(3>nQ z7fQFTG7RV}Gw-q{`EAjr@BV>uA+?>>c;vNsWLpgyUG(gVpM-;)w{&=}43exe=5iBu zo(L8)EMY}YrR+`XnyhV)G4 zB@ch-_-r)&Sh6~S?sE4rjoNM3)%YAsGtS$Fi&*lV9ZQU{aP;UQ%2g!l^FlJ=f%pXT zK~MvePa~i=7-L+UWA)!M@tnoFvOeNcF4~&Fn5vA{-8^3T<5iQH6Zz`sF9PAg&>e(i}== zU2e#3=b3ivq!x)V$e~YJCE7l%#TQcrG3~RhC3pwxsR)09n+kfo_n4gPb2KE z7z_KZMNvbzha%nP<_5)U;ATX{@|W+o<)5$aX|E!L>3^w{2%P65-gDY|S35bm>nKI^ zD?Rub+F5XVj%yvYPbB+To@I+Tg?H$U+w|UZ7xt&~|C~ev9Yb432s%d4hgbGw$SSUi z_XF+~&Oa)5tREIu=1E#vwve_dsm!{4v7uqV)2yvhDT|7>r2}C{Ov1iv-{atTrLNcf zqCU734=8`bi!Ov|_~gcn!;}_)$)n+oHJ|QsprmY_s#0V8EMjn7aBNA&-NI}QCk)7Z zPVW0PchO_IY*!(s!Hmvit=+XPmt|VpVVpFrb8!#oIqr*BDQ5M5oxTRRRph|rP>jHSk_jN17s!nMnuo^MY zjwbEjv!epj<&iC#&1=qOA5e{d+xin+IM!hc9Wz-dt2cu0E$2+Ihbqx4e%@Qxl70g; zQ++h6+6r}XtKS+t;8O^g9hp_$-YJIFP8R#D!zXV%S3AY|S7=qS@zs{XK;!T;uX>m_ zBd@lg;%7RcuOUsDeZUQNGW>N{*}%3bddji_ za(NZ~w&=nH2|rvBK%5#oUEmNi+Eg|eI~Q@r9Nsb8xH15x8T6JlS(z|G{6`&Vi}>`s zK4rpY#yaF%oQ$W3fkWGh!s(KQ(f8N=scJJQZO^ql^b5w6TF2|^udD;{kX-DJZHrHt zQjN8B-ofC2+0XpfHgg@BhkEK==f6+c53K=WckqKfql-=NOZSwkTT5&Lu*0*(d4J&F z!yE%IF?LjCG<8g4a+HRBFsx7?82QnDMme^E-;80gP|dPXp1V}AVbNJD_=^)w(-I?FgS*H=NGwLg1>7^Y2&4aYtJ& zZj~>%KL|j|ks%KT7BR$wUu@;^<^a*c3t`qD%NPm*{P&2mg^p^oA9sw%X%UeUq$pE1 z3(~?V%a~9+q~nitO{?5`W6SA-T4l#4Ig#EqIXPj4-x%UYX~K(x)|cy)cB5me<+W#; zKXT|G-XSb9>8`?WaEaKachLj;;PXl&+77Fgwh^Xt6X!4Rlu2nj1i)%E z*vf6?9%N^=3A$rc5|3jm%MFt5k>#FKbbp(AS*DN5S1pU83omC}lH%~udsQgUp|V>T z;=`-*n@8XvNv6rHJ0cjM7IcvZ40Q6&&D<-5unYT#O0TMJ6vcWyz6P?|9VDWSqiRV( z<2t|7QJ{I5X$FAuTKt+)`gRj-Un8v5Ao4As{BNn4BXY$sS^%*P1_(UwOUY3ZcnUY* zp}XmCsR~@}8Rq}$FHJiK5tjgX8%UW&jRO<; zb>Um|lh3~)Of!~yGZh})i&Jdrzln3rlfzk}PtBz@68wDt&E8CUaU(8FqB&Z-Au=0H zeOpdf^;VltCqm_5vu%#!9g6u$d-c4J{DpL0`Yh1AGG)&t4Mmy6e1D%B{@Z!X&i(0G z!UT{3#9rAj`Mu0p72OnJ@NvwrP^I||KQ+F+EXX*2dOSH3)ztJMdmu4s2kggg{vfom zmC+xekWt_DL|nvxrt{8>hjS7{7sQiM#v^z6i?|THK$K}ddEh0hi|N0Z_)YWrCOrbR zq7}Stc?s8Fzw=kFwxeHuf;&!4^^wD*0BMMs=R|8f;kf+}uHK~Wf#(QqS?M@}3wDJ% zpH{V@R1K++%Gqtx$_aaH`>3UM=;<>skNW<*9pF3bR@hN=r!Z~JB{68Ywpi=zpUU}G z+ZGA2oq1a>Ct!Y*W=zB14;zyKnkzW57y0&bY)3yb`=YGkow@`9QAqWLg3T?cL5IDk_uDHYc5f{}eD@W!x+Y}JV%aSceGjlO)aZ)8WBW@)duJi&Y)&9Jo9jbV z1D0-U{Ns&l+#W1BgUbM?A~yF$vm61Y<8~5PhZDfEOd7@e_8Z`NYHa(p!j^}p-JXst zyP&2+5l~9WgCvG6&#S-Mo4r}?drDm{|Lg?4E}Fd{62L(sWBHl`s@_uegs+evD3R31 zwmNOq2owfwe}?hO+)d)YjDA)fHQ@h5NAm8&fz@R%Jg?>^3K>iWH*! z8%M2kO##DYk|WS+1KGlB+)|K-*Y~XI^6sc}HC5=^rT2HHX%*7f%k-jrdF)!#G|$S% z8^4m@md7UwjL@xteAbu#ML)D|{)2lhb5~wSX1W@ybz7%jg79S-zo>J$8%N72>^mNP z#Kkoal$)pT9?$Jj7^uvb597hvmiH0_!W3Ld(sI6H4u91Ob9-C_6~oG}j~|y!#dPPU zq5fG!>gE?}V67YgKd}D{3nL1)9#Kwj0KK$KBlysXUUuc2CO%56cOj#yjKIy8GvFH#kGdga08VkFXQ-;f3TP-%T#OjPtv?(2A=>~oW> z%AVmkQ)p{I{bc7#@6RE2M;~Z4>~}46eGw&SZb$$lN&M&vAJi!%CG+*64aN823VUV$ ze#CQDCq(H#f?@Q=Wi_cAADQU|!0Klokr2s94Yt$9NY(He#)0|b?P9c}$>nMS_(Kv^ zmh2}9>u9PyKF5MDcfIBt#LXu%R&W*UQM-k?qFPnqh=j~=gq*P^=F?USv%^7d;zEUn zY}YQnQZACX6DtMQ&7v*<<(qTX`=9m?H0PfMQvUlJdgN+QMSolr1*H!^I{!o>GJs8x zsq$KmgajmBpbcIgwGwxB7kL!vaB+dDb|1}kSiT+?*6WP{gJqpW@0VJlDH}fbV-%*RH%^j@^CLHq(V z-OvE&*v=Cn(KJosAJkAu|CuAdpb%IbuHQC>n95m*2;^m!MfcV2SO&3*pCL&_oG>P_t4hDD zZz}o(v@FJle4fb5{tl3HVrEB*k{uS*Jw2KU%1UOa2fw89L=Vu3PBBh}@CP9>J3%!Zm@r$1 zk&CuRvuo>_8&)grzTE@q|3ePq#ILHR6<++DAjmmOW%L8U z{amgeI^7C3q~)g*U*P7wqPw+8K!AP+(9dUp@C;y$nx$Wr#KS&%()rQJHix5R0S~&f zputAN-sMMdrtGMDwcI6&AA>u&dw|!=17A=%0v9!CEVnN~!PD6bN+@juO;N?zd8Mkn zdF91P-yWzLd8Q!9z*7w9s5onF^;>W#$!g;&&I_FvTy;kvay(yiG4QiY;V`7V!u5R_wyIwJ_to@_5s$OX}$#Lp6~$ zs?-W8!)yCH%NGmM0D4>I^psB;n@1LiRAb5omnmEyfm#NXOz7Z{!}&Pwx}Z+ z><9@`+KZT)Z@5y?*AYlQvkPd`CLW@klIhnS{niV^l^pQ9EqbzuGLq=eJQwi*EnLtG zTSNFk(Kxw>iu)Oekzkt8xO^r<2$ry6IL7B<)TW&}DB3X;Y7NDiKri#OYyhum*=Zi^ zczog(_160aXA+@7rWU-`8j-#@;YsMbUl8q#4$ZssiqJ8kfhKBYuVW+L<3ZJvV_Hx8 zNC&QIBG-QY5}Iqdz&FA6cQL+~j~404?ynHjNQoD^na6v3duH3gBbG;;gu9m}(JYyA zqoNw6QZ0jWq)tofQGM_-iAgYABv+28alSMe3bNe^Q(A}|%N2-nY{32@c-RA%_HE?b z_rS%EMVG{Sz7;JWI{iCU1^4A1sbR_fM9nv;i>6)J#FmuTKCJmv%9d$VYGDeJx`u7p zN*G;7Mv=LziDw!z7NLIw3zn4(H&l~@DMFqIAxJda7U3VMHZ1x{;Rnkv(PL+|?pl1y zkuXos*;K{uz6JhV=DOb5`2(K!<(F++zS=8IZq@xjW#fNzv>((uBX8ZFkul0z2J&?x zA8yv}U_svV83G-T{|J(wx%p`?1y~S+0rvTgko)lQ1-ZI8yo`2M)FQpwVvL#v){(gaj{=90nK% zPVe@=cK$5R;kvTxj8^iy_XdGA%vL}Pu_Bo1CGF|UJtJEjPm&YhBlo-Taf{y|G5RNS zZO_eFV1w4sq!JLp^?oaL6IF>82t1B%rkP_^P=Y5xecf5kVQwf9Hurt8Jen3W# zGNaJQ&7ZK0PbV_eK2r)=f#xO8pIn!EI&cb@8a0ho%nyX>1*G1a4RCJg zUQQKJ~vnd+jdV(t-hBP(?qJB1A9Zz0Bclk+S`e zO5qx8Wotv|TWImJ52xa*oA6v^nDD`P1iX^ncnZ^Y*3_!gd8#{I>XH!Zw+a6 z`Bg4HX4w{muM6?WS(gf7b}vA<1kJEfSKt&~fVFf_r~cvtU$|ty^o_xb`YAiCSCaph z7VgoG730_taG~p=>*jc~AnW4#Rdmk@0isN4l`i}c-rwu~IW=GEAz~bs3eshcCp(o zNLwe1Q$rvqacShavKq|6*2oi03gWnVLcjtW+%x8whp$Y-o1Oo8(lh5w+B1_>RsZ#G zl_AtTim>BFwxxZgPEuS?eNFg`M#9y|qtiP%&0N*|h7MJ+OSEq_@Q<&E%k2yw!G(h_ zJ|)hR!n6#q^QzP@x^i6yk7dpcqy0?TMmf7j>44oM$f!m2N1rrat23}}Fm0}pN`wWHQO$y!W9dWxJ z^?&gzsnN1|^IpJUALqrs>b~E~*2R8R^GdZNZvFk?vCG(Z)r75c{(A`-m*{mUp~W?T z4L&E=br9$4>QS(H5wUB`?wvB7`*TNiL}PKjHt*20#!n<0tvp7E3XH-;BEtYsq|~s6 zl=I&%&t*H)4FQUcanj=k$pB+Y{Bna#9wgQp0HMfyr1yVdCA%2dvy$jk`FcGxz7b&S zbxHD2H5fsB+Z%X%=^zZ&_AAHcG)E8@0bv}E0$rg?@DHe7AnKp+$8ZZ|8b+2-vWoYW zv~80HsKn9vE-7t>I9(amfPLOE$K9XqW{S)94&>Rf>0)>aT5V?H6wk+f09}i8SSau| zZ`ayh#e&F9H$Ju_N-XYRxhnc$|5+^2xhd>E{pfAwSYrru+huO9sBYK>@7=+bF*yYo zyvbfM%(2tSvQ>1WYA4x$DS4;fP`l9hwAT=h{yv2vxDZ^;KF^gEnJb-1 znEJO{cRupE$tz7>G+oQ0>OA9J&9wOqwV#}WC1N2(!nmQSDiyid6PgI>doBBWe!+_R zhxW*TyuU&LElkD}kc?sl6#9h!xpv|AzhB9A3SU8-q0EukNSL#PRt$tjTW*g*qK`bE z0nM$51dV@+1~{N;Enq6QagM8^p@2sv{Qh+k|FO~z2wnjR1r`Cxfvnb>jBxn$ z8?8q3z^wZB3)lR=p&?Coytk$@^mEXbQoe1^2+>$3*y)@@7SSm`z594e=0LRpB7vUg z>E>_Km5oq{z4P(cLbbIZ+O?*WULr)_7Og}NiVx3FxTdYpor=BF_XX**^8#WkrC&1T zW;=0*#NhKI!#`#Sen9}S&2-MOco)U57$T2s7L*eNEDnU!-6RcN|IlNB(*3E{g%-G1 zF8N73OTp;a5|NhF^|*U8U94AjRX?NuCQNA!tn?@g{h5}4`dstZqLR#jw=#qCGP9z(PF^*YFT2kQZ`apSXZePH0i zu^qo{uNe2r22I-^IS%mSwxk=mc2`FHwvtuYnAx&Clq54ks+VU-FPNIi+Js8S!FdDx zQ1Cg8wxB4q_YcZ+B0UQxEV(pVtkLr-kB*YG39&ZEjwFh&5hZ%u!k zgLTX_F_N;}DdMP@bKbuHiUV{0%2O6LYQ5p;iqgn)>LRwOKRb8uwn3I^a%qmAFf%< z%$UVP*a5a;4ti33XtMStU_FU}tc4A6utL0I8wc-F*ODkRj-iy3Vzedt3L;raODDa{ zeybKu3DcLnFq4c^-$EL+T19uURjNb-b_c+haTbvdC2>GQ-dlQK?-bTGM&IAxFq{4I zWQ=@s{zfzy;l~;@=BKL{!49mce+Ka6)r2>xj()<_YriP>^Dja%FUj*k%1j%`QV2Ob z*Gl;Ek71M&?p`LPFmEE_^uCSLdDSsAq+rW(jm2r**z(2nev%{E1Bzfh%DDJ%Im!Hf znw`+6OLB=JC8AQZfOwH<8?Y9{HNe=gcm&U#;Gpy03oO=hupyL=>`32m!bsmbuuWSszre(Aa!qUUQ&{G(-beHz z|HI{w^`8{tyGPk^Jk<+(YRGp-KoiWY5(2kAcX?UGYom}BMRYbnPRiIjzSPE;k=ko&U=n~IbIKkmD@{pH=D%{Z(uK~) zN!zm;)_KDPRJ!Gc7gc=A56g>Gpb1=`)oDZN!tVH>CaS+wJbR0{dv*Jm=D9no!#F#K zOG!ZuXDO2l(6gsORXfES2a@3~G7A8`x@I;voW0&YE6!{a)BMK(T`w)qZ1u|lCcvmt z)gV3F2@I$CSbBqF#Mr9^bPO1Q2}*q!8SD4?38|@{n?1F|`wQWE8=~PkKQNH56{W>+ zS{I;XnEwmulx+_HwsdHxQd5`BEW#ZaQnL1#kVAmc#Sw)&UKPsK^5bTui^62myJIJ4 zK3s~J{f_T05-K%3Edys=dvx`M^vJ}u0h&u?OH4_K!`g2v81z`kCnva6^_Rb^$-oz4>OaqhCM;Bmcpum z+#-4Ht6x1Na3Az%NUR;ct19)$3fB@N&SDnQn<3S?C?1iPh4J;L(VS_oGR4Zg1sQ1F zt}{*mb<5E^l$qFzLc;*wg__g-^agGZAWUv{@Pr*Ja{6!Mk#yoAC28~Cz)Ry_Yy`>S z&G|&)Uz0M!yxZbxuJcBUIO5dc;dm@LtP~ElOylfzlZ=hfHOqhCV$^+oC*db372srd9#= zN#fD1zm_#HQIpC6VMYUVgI^P88-Kj2j&AGPokA+nKHao#Ieb8S6dZFmK7>wSrYNKK zwQlH-dtcXsZL~eqIoEEFcXy)5Ul=(>pUyMWKj@r$BE!xtyIvBda$ngl0~;QcKoa8wsqf| zdVp^~xMiTjLo*}h|GR^v!gqSxWbfSmdY6OfSS#)9QK5xjzc_cp$X>%+^zw6 z<+lqm>RiKXZLYVT->*me%w1@YeD)I*%^H4EP~@xEW?Lw$9qLkE!n{G(I&2UoWHg&G z66>FVTqn9L=YE_uYIDcfRehsb<4N+MvSj5ltp>bBI`7$e5o}ODgZDoXum*~67F)eu zDdqCtKkSMIjuONc%4vg65yWK^UIQsMXdioZT6){h5*q~bMaZh!rJ zt?$NFNf_Ykb^l-5SLA*4Fdr)Z+^s9c##n|07DNGG81e1%Y&Jp4Q?J6M$LGNz%`N}jDb~@cjv@{?od89LrKojVFwuN6zLJzO zFk!@kf2cZ2uI4K}^<)JJzWo{oz4i3KTL4dE(kasH^WnPq^X_jIwMh#Lm*%T-+RS{6 zGwVUp#k`{JKib#F7g-tV_fx_fif-LW8|2iQ2r*^1A;S9PyTRUluQiV7%AOhg@VaJ{ zrYJ9;jPNj~A!AxSzoWXXYqL84lVoh7M_3oVNU=gAm&E}Kj>}PJ_NWUwX4XfhCAjRa zm&nv_gyNn@p;f!zEiEeD;?zS{t}o!*UH)j4+BAh)D_V9(#QPLiub@=6Jm3>a>L;Sa z$F{)f3sx=$9EgL{;My13+NPUTP4y}L#a4^f&nl1UJ8^CAmf^-0FX}tS7tr1Fk`>HL zNPX98E7335-ZsO-Ql&QMfO?%^`25_*)rXKJgT4ZhzL-ltO=v z=9RsnCHbd*E*=+Q!6@Q;0A&%aPTXRlX$quBPj&|ZP%?om&sSv{^x-L;;}Hup{1&Ia zCXV<0M)Ngm)wZ${1}=&oBa_6x&|th+4|IU3=kBjb3gS7Q_4lk{)Q+1kO2FOZVl zTvcLcNzbY0fb9sXXlxU{=V@Z~bf8ycGD9I`XHTlaA<69v#X+l!LFC7DGvq=k=%(C7x|L+21`WPqB0(EI$dT%e8079DNoS!j2Vf{k&L}n}X=3>Nazm(Mb6zV9R z6}N`Uro9W?&13*{?eU3ggZ#?23EhBbB8M;o1=pdFLV&v#$ z$krJLV5y#}vf>n}o(7&ewRhZ^qjCW391N}alT?4mQXbCk`hufZ^5OsTI_xsZamDU3hi9}2mzqgw+gQsAv^i*3bXX^Cf~@CT%zmp{qQ}v) zY?%&9xSfI;*UInF9pew}Nnl~-;`~mYx9JxXhiEU`%!?t{rmau1%Y5aY@8q{KtzC%9qU^aa0(2h**gfJgvM0MoX{CTSAo(aX=tz69ihT71duH=t! zC*A{Ob%WC*XG-nh7j<5j3(Z>WKKkE9JS9Y`tE8Sk>1L$D(mOsDy^SKMeT=;X3c?-$ zl+fifzgk!3#S=e#PH{bql-Pm6ilphUG$QlhD)jrbFS2jRzfXBH!_3V^GY*pQ8R*mv zQm^-A12Ffl&NX2yO2e1E9P((Gp2V8$33BKN7Q4Fxe8y=uzg_?Coy%k~9IWVUJIi;w z=0b$vO&5hyl9Fy_UCmZ1x$)*~17c47PCM>V_)e#dxmBM~3k3zl^mO~qKf=?qd}rhN zN5E@4{c>Kd|0_p$XM6gmzS>y97Z@x7odDY|U$-kCyeddUs6HBK~xr z$C!2Qbb@_K=fOcf_}2B)jFkI(Kd7t|gHmY>W@XNPqX@tD?Qk8p^lrg7$z|qUKh@qG zzLqhe2TdeDW)GJmUg2UO0ec!8WTFIuN4o8WX_(#jJl^&vUN1_0OfH?sy2>}w5{ak?CDJJ1@BbFIhMwQjZ9qXY5^~ zn*wj}1}ZX}gH{HxA11O?tpQzJ4*kjRRTgB>3gGHX|LzNW8=)#xQ*rl~w0nYlo95y36rdIS1auaX+z&y+ForhrDI6y}s?u_M@2Dflkz_?)QW^>`+rXN#1Wn`z1C zj&?fWf8_{VvP`|jZyt3jf3?zP-5F7U}`L_T5tN(_%HaT^N}I%DOCYY-DGs=sMQK`^^id zJwV_TEvGHo7Rfv0TC9gM-2oyQy9DLfVjXAbk%aA#@uh&8wCGc^os1HnB%)lxu*82K zJOKIm8-9GDw%8_z#i&yM%KML78~CY1^Y$xp(_shvhoqL(Bb%jOW7a zw6n(-Cp&MiuU`X@?|8vO(;&sHA?p}Er@F75+7-pP$73FtSD5Ry{intM@{IK{YL(dy z9__%j(`r!qTY)l$kShp*xne{^g?v>71X;DCs7=GcA_44u0JsJKXzWT%GMsZfA1%A1 zYS0~*Q1qYi5zw$9Ud{<50ZON{dbg0YknhS0f&I2%19{Nh0|botk;xHrrIx{#Pvp_3T!SIE{R`i5mCr|9d?_wwh-!BU?k< zBTR1CoohUP3H~)rpmUMFj=<^x%NsU#nMI>L>QcOf^j`RUaJn_)l3Zqw)SQO{DCpO!5tmU;fwWUS4lzsga3w+r$<+zt~KOz;& zPdQXxzh*8Ibp=ogo@J8tn{feD#-J!;Z+{O6ktGN{RbJ&@pzrM|q|Uj=33SSdZX~T` zV3zCaBIZEOFn*rdtBYnA@fDi5=h)xZ#^=eiVV|W=XtZZ5TzQxa@6M`DV^t*2DH&L& zhml%RToI(Kg=xmlFxgx-m(KfC`JY7%6YaD4u6fGR;m%dPoraz3VdEbr;{V;uZ&`d) zp7#QQsekR({5Wttcq}4hDKc*{BdF#kyXsA?q<*smX&aL~$t%fkwZ3-K&o5v!y)70! z_r}%zD&d|N90e(YvpgmE4cw9cSMt<39J&Q86V>ep(~@%7d%_-fLHw>vCpYA8u?gR{rX@@Am`! zByf}z5pN2>Mwm#>meQk=md)~mnuYM9+X~MdD{O*bbaF?ZhPT_p_hw8Vh1sT=FMJXB zaVekvp?piQICVLp@Qpbp_~hBhwdN6Mf;nKPi+?BM`RjMVUD)9ki!`;r=T>5{W&g03 zOVw*4eX&}qn?H1SnAg|fAs!cD4S|k569jGw-cD7=S0JP|+rE;7)56EoN)6jna{lBq5JJp9kW=Lw^rz6cpg(aL>m!;8d!Q|QsTi>p(_T4>8w#BNhlxngIoA8)WeM?vY=bWwW84r1ja2upg`@bbsy05Nk zDT8E|VS!Q0F7+&Rio1Pl)*nMIZY}2)+CntBX==mf=STF@RVf6P2{Md!*}InAGr zThIqq)%l;M2tTC79UI^ZZ1hF498xf{#VUnLWl+3<f}3h!X&I{ zH+n#dfSB}l&}{&E&w`0p(B`-2qOnE8i z#Znlh{+Sp~tul!R0EfaSU<|-M zuYOH)QZ&f0oSYOT=MOpJl59&7RwWLT!+(tD-zJEgahB0;=xnQ4t_D|kD{zb$rRFji zY+Gq|-Ff>zSG)E zn9B{DEeJDhzqXs z_WAeT=MnA&vG-qJzu~oMVyookMZ@)-0!gM5YeAj%-PWvX0b)k4O6=YgfyyN*48LWx zx^=8A4FKL?I4BW?jgNBgGwd<*300hA1-@E;A=#+O01#qrkUBf2l572J^O7EA&;3#A zXEMqoH90(RxuUtka16S=TF_j&E0e|{B&U< zJJN;Pbf0(rKuuL3sHmRAaOM6$eU#Np!P9gtr^96LTGwY2Dkc$AL1MgOR)5FeGX8Sp zp$Ywz%sbV4<6F~rSrX$!hqREwoZAbIo_j$DU(Rdonk#HDi;l}dI|LNlrm@ucMzX62 zHB{)X?eQJ0zbw&g{J1-FXF^>aq&~UYTIdl5JVhROX59H_Jz*V`UqBqi?ofss8u$Qu z(bjI>R{??BA+>Go3p3LZt9P18>Hgm*U)`AeZ`I*Hr_q}Rs(ES49QR5Avf$85X+vWWs*?pW_pr3TW7zM#lFvq1$q zG!i9DDRr4nY@ZyqzC7~YF-)U6Fq+j9)tuXP(~M;=e>){?LpiiaaFG5V3} zkPh%2zBvfBDA|13LDN8eJ@@>c8R-sp_ui%Ed3YCExC_vj zB6eA=o`sA@w;#XsWAAp;L^@n1g6mR(^oVG2q=RIoH&?IL#KNg%r=r=qr=TsEN+Jey zh9g+=C;lBrlz~Fu6oA8^)hfZcqO}EK{a@mHQx7lp@KG3;+&W=66TP-d5g{JSk>$9S z1kek{1^u+Yj9nwB7=Ig2Lw;iB7|`MQ!aA{tiDs4+gC!8;;Ax zViz^F@(M`^%0(5;;={+@krUBD^$^`La_`T4OrmH2HSc&rVTrXbnoKM>of|Nd3*T?7 zKP(rMc;% zEe(6w#4LYh2KYLz52CG`Iz)6z5(r8&zEW{ol^$0UwCIdIPIg*RK?w`C+45+33N?!#c zH@Z#uFz!?w_t#LSEC*LJovA0X9Lr<_KM2|IM@DH{ha<)QZ(26fW( zE?q|f2ouJk2#cj7J=?5_^vyl``CZU%=_}(Njb=zuRed!@&VN#@t$V*NE}tXFIw?_; z*Y)FfeqA2#^GN2pAbaPu$6`u=P7Jt*q5?s!lLITx`3E|G<_OH;pi)oVXsXXk!qKie z>)eGxfgf<(rX748uAA;NC&5@t!Hq5WbDq_57je9*2)<}m{(zexhwW9krg0y^;?$+0 zy>6yp(BYrv=u)mV(EcsBXkQ%MpmiiI8DG6S8<7=lgi#B&xzderQTVXn#eJWs)FwY# zS9?1;X2IeQ2oi=gU{rTqG~)gE0!nvc8O?v!TWCiW{dyMqt#L?iC6kcO*%0CTM7%1h z!7m+G!(D~=sgQef(fSYMK-xTtc9xCKBB*1+^$%OdW*gwG!dO5N2estlgpeGZ&5CC znu$EJF5rx!k^ebM`Y&bgcs$BNF?!{##2qKwJ*(a(3#DC4>IRb8-xmSi+oL=^4(~DC zubjYdk)7L8ajnSt-WDRI1Br>Q2Bg-0jZNFa-xkr=>J2TEYBkAITRP`62SDgttdU%VWZ^dGzR zOMY$KmHYc*B;R7<{}AogQB630^!GLx9ZEN-AEZGF$zlkd6%yP*RbS4(YA| z5(9}Lt&AL9gHgh$0UOWxKF{xWp8xK-=l=Wt<9*M4@ut;PM=ebD43#&F@}u~ERIC2+ zM9*njW+S+@fJ?REs%wt2Cer@a=!;%V0^z{0r--EMr{Tyz0sb}?MgXMgA7{j^yNST* zj$nPbWSmlwDf(iWp|^h!(n7Je4&&BZ{@F%2qNwi-%fFA{6MQ|IDN@TMCier3qZxSoD>B}t?3qs zHN$^ay6zv=LL#;}ezt|J6w97PBgwfPlXqeGd+n>dcX9fF<66b>{qb`fKSddt!t9f& z#5f`;uJ%73`wn>FjImqdYmh&%XA>O4_wK8&dsEGu^1X7Ee;+GDv?f#Lu$xyX^)($O zt$7if1`TMTHPpTuBXO};pi-ZnSNht?N|M6<6D$v{6uIc4AIVd#q_cWec?+N!*M@f1ex-?UO9%}QpvP=g+#z=$py zdE}w=4|6MmKv6e8+E)apmiTNI#Hy`$8lVjjrX1%v`qz>*gG6#R{E@caEyZQTN?)+$ zlMpqC|JBpyHj%XzJ?gT5{(Og(X{sWS9=2^qV%{oI2mDd7C%NOCV0eH8XXwo^^-s6~ypb5*V^DFj z+aTT5=U)qwb<4^~TN1~SfDYj%6-JKMKq3HQiN4Bx&Am$hv*852(bUs9eu{x>7|PRg z!FTd&xA^9llMH+cqlBQ2FLc%8fz^(PkV|D!0)?r4ym(S-ZbzSNN%H&rcNJs5?#nHn zLm643tp^Lbips=pVCJCb(|6Zr;gIYeL<4vJrh@Kk3ADGn-2lvVdg(kfvVN>vVKRyZ zHsjOqEnnoH`+jI1sR!&;)5SMY3K%D1yq8D%wV?fgCMcb3NmlxkE^DGcwAV zt3O3UNAIO=k^mh4sBZm=Qe`sM4!Yeln`)R6_pUj3(^nixKBMSnY`A(gWL#B}EC-X@ z`=QTCdhiEV^ZbFQVcW$w@y7(~>m5i7`E#1BFs6dk@$-3LCzspC>Xx+xfi1#BDU!<> z>!S(G6*9~&Xe=)NtV$pE+`)D6UP>A>4E3~Z+!%ycda6DGYT7_ zxVu4VkqhZNIp9C*f4wl=YXKx&)kpYblng5E?!7P{e=ZUxv6xF6+&02Bc; z$+yI+xuiy4ueCqdl1sqM!413D|Bl8f)*JT}mjPf;1H7$zk7 zHtwbuwTCW|(*;uQaLB)IV>U7nl^8Ckt##WF=JX=~CIr>jU0j)1hfSiV>q4L5xFw<1 zQ*s4=b}rMsZrH1n)aWNeueifKpFd;W`9>X8HKQ|HZ)p}A!%(W|ULQPhQgxQ$tFlCId zrb_u=QOY6qc0~^mIHr6aknFg^J+9E8jJ@eTL^$5y@4CFMt2?y3h9*_t-+KEk+3B6P z7uI`Z^Xd6D&dXC?X-z5fi1h|;JQK(++YgMu9KZcmx-;|e*IRi$qiGUHWBt%_!*78= zPG|rqIEoJNu)2zhw~?9pyolCP#RR$j(t+=)G|-FQ8vrfa_>!{)ea6E|>v@Y%(j_qc z(=~AEWm%(uQUpb%ez^p{ej`6qp_&-}^qzmTs}!iFLXw;Vpaa-xT1J{~(Yx~~V)r~tYA6)A)018FF8eBUQ(9ddr~!F*YEQ<2;fZ#u?8_0ffgj(hb?g$UKV zO5_V6^{_jtx0^irT;GPJ z^dHT0TcJox_N>iMS9% z5ZoJa$lVZ&Ve*#?9%N~*?L5urxLT*};iC*n;@w_woT+wzB-Wd{9v7?9c!+p=TQxob zh1GOXg`PF2!5#qwSM=yJx;FfN`!~wMCdR+$-8>dGLY4?V?x~0bN9&h*t;MMVD4fK8 zkTHq_6q!|@?6@S@mJdmI*ivm@t;=xbz@nL-NF~m;+kJiWefn=*UV!*fBqlb?sOEK& z*9F>MK&vaxr!KEU@gRrb$j-1yU)ozxHuzt~)#p+}+;yHk-xI`jmh3~<`=l~SF+7`g z;*oZYg2m%uI9)-x<(8KbN>H?$L{R#pwxe znW>LIUjtzC4zr*<7=xcC;boiG9SzOD?obnXYtRY zot#TtsD)qN#k~%#PUcImoMS&y#QF1ST1{mIhMj#W@IRZsi1=a)(`Q%Bj!yprgAtk4 z=L*69wh@8w3sZ;y4f_V%&2pGVTIsLoPX}|0jcH9_?xrh0$I9Kw91X9vwEJDIwSGEi z3E-uGp|DxJ+}6f-GI}5CguITR{=ZuQ&(+0D3X9%pf9c!5U%Kkf#$}M{eS92{nj)uA zj!R{@($$Jkm-6DjbFYZYO^iQC=S&BNKrkf9EvVbWW|W_VA}+qkHSlk`o;PnLlqUJ?b12j4H(uU&Q@el6Op z&jGbJL*jm6Nbk^>(fI2hvT)MNbEj#z=3NLE-~D?rz@&;lLY&p88$ioCC`U|vr_RbwqS!+lW@8(Y!*>oqc7Vp*8< zX`CcKQ#K%{0Z*(0WY;P2DdB3Mqj=R@By36fa{VFEzIOjZe6pd$9QV?ETh%*+9i%s< zWy3OP_+hJ?B~*}M1jIXE|M(Wj?@+6;M$;;%`y8a=EXHF~Tu6Si`52z=>zb49heRTe zk%r4%!3mSWpo{#{386zN9zodn{13J=y%fVk;*S8`n%6t?@$4Br&30iS3#`adL=nV7t)2u$Q` zD5O9q&s6g)p0OeYsAF1-(%qU*(_G86biz@^6C`8yB2?bV*Q0v6#n&(UYVaQ6SJ$pK zW$wwLAduJbpN_M)7s;EW#RBKbF7$hrVMPw#|BeN&> zN7(MShkgr9{ngfZj8WTXSjk_Dj#Dkw7gie8AIfM||E8i=Qhcd<--bcF$1m-;*_he= z!>(P25*KEK`+R|EL9x&^?t84Orq8pw#iWb%TivD{+rcw;E%>|n0^}k{q?fM_34!aeRaM_l~XO4CV<<<6WLuyT_upjCVTj+whT7trz<4C zBCIo2d~fb9Z>=Mjket1x+m;pn6#nlUErW3N?*$V;VK~Tqw3xJJ_`CV>&zlL?ndQK@ zG3+=XS)iqR-sQodS_|@I%kVgZdgi**%d0XrSQ&Au#(S|SM|%Ak_GeZ9M~~9_6@A)t zv&MwZzKX6tw!xQH$c>K*xYS3N0dOxxqlYF*sI17k;NDYxrSR=TVhL| z^ZL(|9^Qn#qF(;k6IkDakc^~`Ca9$WcP{$Y?U& z@_f>a#ry25)!IKq{pak3OgQfl*yirs>o%tj7gu~X?sX-Ec1CTGc|f*NZWL?EnNPb~ z%B%G{N)+q<;6rswI?a39N&fvVN}ad}*zw|mqb@2xatl~vZxweW^Y=Hsh83jV-L=>d zQq)CGb;I(v!Zefva=5!5)(3QnK`^QlIH@bMP{lk_0FI9%ux1q{3*RP)cAh~r4ja7Z zafLL;``Jw90Rb9H1aY1UyClU6(nQKz4Fe1>hRIS}ef9 zI`V}RUS(e$&7u9jDQglwOkC3L!NCXal<^~4=OIGw1(nP4x+5kB`Q^Jq1cT?lT%vkG zJ>Sl}HWEJrA&7~pt8SyXm9jp+>AIy zRRfRY0213vl;#G=|L9~3;mD}0OR2mBO0OwvEuUS)1v6U(c*@YcjV=JY8#;#7a|Yp zCH7X81a;;w?{hJeOqYphljKI#s=*c$>VJx`Y^vNwIq#YWhGVt4Pcfavg0tB9d*5ht zQ{c88ZVds{&>nn4zU$53+8G#^Kr0ZgvL+IxGRUh@& zP@4#oA!O#<5}B`wUp?cQqcFe-T zzhUUjY>C64fe=}$C!Q{9CekUHA?6M?EVT2~nLhXZvu`Xe7ZQ|P^qGo+#1ma{7tTrp z9#D@8x6uwA%B(@*M(!am8L~AN0LQtBSYdjHZ?kYedOU|)@C5Wzwx=k_H0>A1FoUeL#0v``QQ;*VQKsFshTkix@fi(WPP3ZE1a?0kad8=8;1`avSe3#}Cl)vo=HWNE@!R0lu>u%$ zhe&FBg5Zd}T^@MU19Fs8_;2&8CO7-j3BSWTGe+elsv)cPTdRY3rG}GP59kjH@9>1phM267~T!ojKJwE!_c@TH5ebm zmpRzB@p4%@^I!F=m4T87LgkNfbW`o4!-AjRnaM^@dL3as@Sh--ds*Q*H=AKryp%3! zi1T@5%ACvbVlBKW1<-JJ86PO?xuC2vp&YWOaRv?!sV?(arpd(5_|Y*Q8%nY-Dy(=* zjpU&um{tTRu`SY*bFw7jyDcI+=k9ka8_VNT?dA${H`V6cGwChRwv>p|W|(pPF|9Mc ziINCbrYKf#FOusm?MJ{?eapi>sK48GBfOMyr;MBLZVrz+(CL7W#f=e02wKh-UbIh6 zf+s^_3tWL~=(n(0TxE31se&WM~^7$ls{a{xfo6u3?Y24jLaJEVz zdp3s{KVMVDhqTMy5uJsT9SPa+3_bMcYj`1DLwV~TZas6M*@^xv@%~)FUJtNlN?*07 zr^wkx_)!H9%<=l-=ZEsw2ES`4p^g#q=XTf=yn1T22H*!6tiA3K$-!v{_B6^QUB?4; zJQRfr-<#X^0~R_l_`0{0&xkpggUAlZ$!bC>L7e=<(0ah<2A;f~oRe5efVzsFZf2{i z>Cp3UtZk;jj!A1R5e}h5LawPKjpSq>Ya8={1Xd`S*;L&}+g@fBQiwVA&h=06yG!@` zPHUj?gFaM*p3hl;3qb@h!8>$#}X9g%G?7tYwN-wA^c{^R% zU}$8yp2$cs^L&E8-z+IjdZW81ID9PTyrH$tEhE`SJ{Z0((NRbsA;UVVkWPW8$f?Ai zwH3=3T1Ay8s!9uLqQ9mVqjI30I zd*}AOqC)<76)YeWSQ-D@zfHG8+7e+Q2Ih;O8P9Q;7K+(@pof&8p|Z3bl^;?SWbf8d zt=C1J53$!%j#_QMNr6fnW{IQ=@dN{TQoC#$qfUn<+Y*}6gQE_gwtdq5_3W~NvD((( zotX%49G4Y)81E#!@+pQVR}4Y=fyfk?m?-W`H>l{-^eVhEdNfQD2<}mNk}(E*RW{Mq z=hhf7*YQ^r#k~)Ip0I1Mek^`q)x5(6=d)*&IuREA^NT&L12f6NT#*pDG0)pfElVR4 zAo_LnHYJ9EO+OZXO{+5&a3%{uU7Pb1;G*%qTI7AQqBo`5jbVs<1q-lUW5Rx;5CX>7 z+Q3W~l%rEpUaHV>k5c7Xrci<9H)ek+$q4GOz@T+tfusp^TG@(N51@#!e-854^6Qse z@p&~BV4_m8QOYeFyKn1c^+z;ZYhZ&EqfGkdwJD*97SfwR=x9LLYt;YYn*5B6$$!?J zEqOO((!G@eRh%gcJ^E|+P3c%nIpv^ht;4TT4S3rnoXJRffc+^O z@p4VYQcUs$;ynm?rvW^eac*T~9beT{;QEF0#{5pHB&^r!u1Gs0mAhhGbHo2x7Z17hI1X+oan!HWJy37xPTa)iUm!8XcepAh z1^2$V#Q?G3b-$`iCY=nAuKl`Be{n_Cd+uNRxKpliFe9mSd|`ve8~28rcQc<3=_cLp zRxai`?*827jl8~CZt_^s2#YlYxOEzM+K-1_({rJfoZ#Kp2qKlNln3!czDpS(ne=MQ zMSbJ;raP49U3yQK`y6%Lpa@y;IV}Vk@0Fw1a3HoWEe(pe#_r?0GsK>MFL;#4hfjNw zgtg_asA#L0U5vtE&Cz>ogI>Bxb_}Ri>~59!v2VU*dUMGY2c`-z8<02RycmccG3>eD zXww%~-4xs+kTZIMQC~8esP8go@XzC6grz^iO^VaA4!+2rbw9 z(xXaNKJUO@J+O^g>kg^azk_jdkf1xuz>G}%Mpat%>^GAo=M!=;%+9IXCf_iFyQdr@T z2sFy9^}AoqPS(i$v4@2Np>!kI3;VY1)~Yig&ns2w;FI^GwZ4tG+_vWK)vFD@+ncO!&YuC&e#e;-?!TB|f0;gEubxzJMz`|T*-wUck znMQ$G;9@mols>Aor|_PM-F$CI-N#kWzON$QOA4iGzb93%7eijoDkZH*GPsosw-?iwhY?|p@N5lL>4om1*f@`lLLL(`2+-9ziSD}#%PAhV%}ph~}C zYo6TirCX;v+xqw>eH9CUM3JGOSLJhx%s1)JAn&QQgv#)oh)m;HA0()h8W>6x#rp;% z1uzN9mzsv@oW$b!3u8GozdtmT#J_wL&-RCD3aJ6sDds16Z_{UX5K9fw{mgdcW3lGe zo7NJP^z#?gOt_)3ji%ETz-NQ_mm0u1t$%3IHGVJ11{)w0RZE;97-W8Y;fgkT{y^mk zz{GWJS)M^U(q`^gI-QAKK>rh-e|=8~fz>I@<9RNH$%291$Yv~ByQQd=C@9~lV_Fbn^L zuR*+-S0-X~BG=K2%L+f?0tn#yrRD)dn1*kTHA}qm&TA(erVRRRbN0F&`I0@sVu!o> z+_cWC{AQId3ab8ArdfR^XmL_N%{79OnTt-+t@67%&9@saKA_q{rby^-kD)K?H3o32 z0Xj-rKxeMd9ZOr~;@0giiVl9cbbj|7AE3-ho9e#o1E#lI3Y)TTaeE=-4q>t@i`Jk& z2Ca+5`SW|Z(@NRFF@8SbPBRNIN&m=vqentRiL}*Q8mkDuKV=rsJ{)nFgOdFcVuN<> z`B1(k9$tc!aV!GLJ~OosNkI18a@vc!9)rxLv$Hy864Y8m8Zzt$+W87zfZf~cAf^bI z!)nT)xFo#QV*)r3oXT|mp4#t%QM@@$ieu%XadWruU}j_+v=&}N3&f`Gs*OXu(e!W)BQl6C*rvet~6FUxte{U;8Ub%zN}x_=IgF3S}!=>C}li` zlIc3gW$rk8vBPBehB}kv8n4`QljnLEOI^~#J#T^L;=qReuY=~Gnq$}Gk_rxL*s|3C zaul3JbN|BGE}5w>cC8GcAEa?-!g&p90jUN_NdaLklBCIMLPHsV=|^pWvE@R@ zVG3kXQmJ;n%d&CrFX5xS(Pff%#QbLdd5*T{wl)d)%~eme(vJ{r4U+T`&cm&4en$O6 zv(*dMSGJ2~#fMFbs1Jf-`@#S87XskNc?DUhXEC@cLTa=4+O9fq8`xIIJ17hRvenhb|+esRUj`ix%a9^(>WwkDJ4#7%D$ zz46dOiFO$BOW4E5!jF4P3(aq_T^Ovf)6IMx^$z@Xxa(eBVzuv4j*vC z8EC+L_XF7%`ki~_QC3*7jU4U4R_C@8>@EteTz;Lm8WDo}l@vxjPgqZZyrv=LW=~!1 zPZn9IokOoqYt3?8$3-Ut&S^MY@|^{s@(2fyuoeNR-^wwIvaFU_u=vQyOf4j5U-eb# z=hccjvFuxc`|X)?VkO-Kj?x>Lai{QUMXYr?|qkWAwr90 zA6;?DE(ziLeHwf!Jad9nju2(>d*i=&B~cZ6WU60_Dl~%|HOD57oU?%?EuxWAk1+;p z!@E#F^jP{i#&OkPbx{nZSNU;)uJG4*0E}qsy@!@(nb-2-Bk+c>D%ae*vyF!aFrp|y zTUJU7;uiphcJdTWkKQkU+@)UhWBJ2qG;7{|9 zIgCnZ#ONh&z;CAV0ZO1({5|T2#{F`U$%;{9n?HDn1OX5kEq*4VEkGJIWE4xtfik6Y zPZHS?4ZPIU7q%rjvf)lz-cPJhb7x7|FdG>HWz$XkD1O?jt0Ic(1?iqkFb?V_nD)L= zm$A$JBE_TdPv@cyQ{Hf9L}2+ys!*Z~svw=0dZu?1>4bE3WH<0tDFEVWer$B$qIlgh zR*epGRYh!`TR&fm6hT!Tn(F}Lo(5$a^tzBzldU9Cm}E>@2}3!bsnL2G73v&fKV%(~ zUZQW+L`8CCsUUox6l|B4f=`kLr0rZT|9hIPsTUyL~4Z>C1~<1z8fbr}_Kp zpi2Fk?7ww?#sQyXSD$dq)UHf|Sk~&@^xamGO|9yTZ2-hG9tnh_bsf=B%)?yu#NZu` zp)e$iV}8>0-k8QhK}EFbKb4om<+XYjshMZA9^+tvxDq|704lp_Ixx|;)&xND~OWr+(#c}xLqP}2XT2Gc$K}O}o-Z=xkl-QRM z;!cx#=1!CVZ9`EYWP!HPPMp-oM=@lOh4Npk9kov?aD6bk3c`h}c7ss!l^e8)xq4Y*F+V|;Rgsc8-U zlBAsWhp*sAh#kR9>NWE}MG^kLi7DcSPGJ=bq1F?${QlU`zj=XmHAZqd)*>Gdnq3jp25pqZ&%a>pxgI z8$U}4i^#(**WSsc&@L&Gnqy>}74swhl@zq3{mMhHe%Dr1?4B|7NTwwsuuKjSeTX~ZVpLURR9LI6>oq7$gHg$MfHXX4fZMnRFz(wgkc1jK@a`y z@}q~aIue?vLIX%j|5{i5xzxLt$@7};9ykCv-(c!#+U9Bvps^9@jmb_uplug-z`Pd{ z>HtnUc_Lv;_6@{ipL5Q>3^bfjX}IzHp;6^ua}&e@o>dIF2iELAHcz)R*T}PIC9U`( zX#y1MwLGv=4QBF>+Pe>6ed7PrdstFA(sAB~62rjm$k2iU_tZWWKJLr@{;fAevPSQQ zI;c$RI}IDHiKoUqAhgAQ=*%>k+v9y5(L8Xkrba@T!hzQV)H^S@#1oq0;R<|UUizjq zWwXnnzY1IC)u8UrK4Z+mTp|3D1JT6TwpN~&M~(&l8?aRwdEIvT*}OVW-{B^SBFGO( z1Y>JQlCALa{=0~X6r%=psN8`xyP75JDV?+xlI&in=uz10kytt+s}-;6FXbt z9lHhs*rpdr3YAPU!xA@>Fy9IDmH2l7hezc35-c}dZfxc5qY8Z|vSqe>>dt5j(5ZeV#q^ep(M&Vg zN;i}KJ?2yon@f;=*Ktt?xrSpTEGS97H4JVc^PO%l{J`eMhKeW#T6~=9K>R*rS6n4| z>qSY!$mP4?w?RE-5%anv<6D#?R*R9Kc~4R~n|k42mCMx7Az1kI<46almuaVDXQU1J zVDbaVwq>9JK7J~;^~L+oAiqssg$a)9bt$*)+k8G z2xb(UVc#l1 zVB>kGEOYOD%yLb~?_i(?bea64p1P`~eIaGz+kF=s9#~^@X_aF(_*o1c^DEKGkK2_6 zh}Ux$s74Cf-Q56te~Pm|k1+Wl8^AM@1+9A)xeun=jNHIF{kqnfAtgXKj@e(EkNx7F z+r@amnc6Ryj_&ankY}ArIZxq4iUnW?0CRCW$dQBnSGKmjDP`1I4u}k#rwLKHH?MBP z(}3)izmitbv>7x|U$d-$f+6PWHvO3Y;z$WMGZ&FPu6qwC-MwgPz^+AqOKFEE4JtuO z!8E0=6(0<5(%I&tUaIh&=4XA?R@rm`y;aimpua#weFeNRN7MTD48m6r+m@h_Wi1Bp#y*_p^lYZ>6a43chJ_{5|6F!AiMZp-;_4=?JvjgV9sn(Nk|a4 zFiGFWLVR$f>0yHGQ-?3&tCyJZpO zoGT&%PK6l+I(l&nKTX3mZ$Delx~JIxrh$(!o{8Zy@cj>SSV8OUfQEaHv>8iVAHEw~ zNaw|W(vM2YGo;68u`5nMokVGCkuft*mJ}h*5h|-f6Z>55Tha>D~2I# z<3Uj05 zLGDBL5?q(T3NQgEsqs$)#n^0|1x?+l1f$&ezQq)6l0JRGV@USN^ceT}?fh8EIJ!Ub zCM;}vzh4j~MbL%>Xzs0qDM=P+kE8XmIOP8;Nsq8D11AVgpJn8Q=Fw*$^^i8h!M9W9 z-2{rDU+zLWNr_KZ9qv+sq@?t69h@zC}D);uw&)jOsm zqi82Hp-d}rZ199>bRfndNL>KAK}d^0A0Ml%^+`#Ix{O}iI+036m;w*GjE|_1zI}ueTn~B zIll^ufePsEGX=#g*F&kN3@0^3C1t6DMwE}L0Hn^^zkJNq_bqe|7U~unxIW!Cn%3o> zdD?hoenS%BW95@vB=;lFNQ835dki=@Bx%j4%J88p4!uA-MRj9>Tm&}!kRx8p2>9#O zX;9AMHm9>M;8as{z)t+ZB~-{?Qe{|Og)>?PtU^BgZMMth{$Y03yn3eEz>9Es5BHfn zcJ`{}Z{TiVZ$%^}@ycv2# z_N6sHQiiGRj+G3Bhiz5-kVH(o;1xnwCyK zODIY+N1BYVvK~Xse<6FXaG~}6=!m1rge`1GJgUnE=IU~bQli`)Oq zN0hriI3(BRxdl@!pp~`R_D;yz!gFlL#9p*y8R%3JAc`AMh;)#ItKk<+25f{bnslHs zk7Cin>W!+uSj23AN8-}+Tphx`jpHqLzkHmfDWBRkzDne)R%h)moedNWk!1#mAV8qM zRtCqLKBE6vl4YM*KKLY$@mY+~3_-5Ug6=~F{q1Lr+gYbpboOlf;NyOD*t()BHwDBA zOZ`Ar`>EW?%W$tw$8qWW9FOI(|lOD#HZ`kb>ZIrDu+SI!|x>lG6|Yn zG(2mr4Jo|cObctoy`kUlJ{7o8gr2+=7VZ<3J1p-P0180HGEMTZ!Cxf{rbDtPS?pfp zSN%tH=k$%_f6Ff_L;4;Fe*K_lV#2(A8rXAF>v~=#uULN~`#zJLNjt3r*;Yn9gb4Qe z^@tnij6MsAM1dDqiIdppE@ud^H~3D+L)WB~&}Tz!K^D}*uM%!~VYz_DyvJYOEgf~B zk6cgswWeNB$~p|DMW~?5cdj&VbB>S4FE4j)La})KN(6-40MI6Sm}C7vRQi8dX5nWQ z`pCy1+9k3u+%$L7a)(?J>P9=%wol3P$R#|vG_Tlquy zv>0#w$F2Lg=WeP0$p_cj)T(UIlT6f=CFWtW6Xq5C=GXxK2+lwQp<^qT`FrZ96B1G= zsk^JLU(r1hD*!0~?y{~P`q*^2Y_aaADXq$iD4DH)Rq{PSiG?-_o4>Kd$|Ujpw>4cQ zkG*>JV80%J&oSW-(9ItVCM^RL|M!fj5FiqyU0=vCBFY6Ini%w`0ZQ|L3J0cMG=QG; z`vDgL5=5|JO>>huxX6?sW1`7tv!secC@2=@>Tbqc(og*0*>>U3i3A z2}c7njeJfiNIb&U*`dvrwCsdBKQ z1}d94LB{!^VxZ8o88MarP9?83dkujPog(|nUh^L1ystiBtLwEzu7WhThHpD4YkCI+ zGdKUqc}v{HgoA1U35nu7N&$b#bw6_g81}uGY;5$$8+GdbdXe8oMxAj>wN?Cw_}li% zV?_LSp8x)wI3w_lhfmlG(hN6x9nH`2K-v=;lG+loKx(94I6 zY}X80ztJaKcAb0mQP2oIW|#UjqWkK3iscCP#JAwj0c}k7730vi8!A+d5sqO*toDCi zZ^@9t@bx>O2x$XpmUPUD`ay-|=*h13kOY=8{6*W>o7_0VjzzV_N2oee)RT*O<|p~2 zYqOZ}R(a;s_uY2a$&KR*S?6>1MH(irr)gb6$9wck3n+YdXx%eOb&8sys(!}&*isc^ z_ACu5OI@3N<(;IKOmyzFUOrlXMl07Mu512zoDk8)Vw1U%g{(9aW~$t!KIKrRaad`~ z1nRl*j$qR_w$G7r+q=lE7U!M$sfRFPti;|>z_P!@EM{fI={M%X#_pH9%HdUt+&8wy z=RudR+244!Hgnz|ae9r*{VtG$R#Vs*z^v0MuLy3TApUOtHy%P&{V73Nz5i@U{?04c z-@gR|?7wMEG-Q41*^0Dhi1(auI?SG#Nn^!U1t(;*D&^3`;woKK|Nmobm%h*9cl%p= zR&M>dOTF=e6y!#OmYH2sAv?@@NL51l8TPpZw^RWsZSG{hF@F8nn7N`yJVhCQcaTSJ zlV==UmJ;|I=5E^5<#j^Gr}g53m@a_gBZyp;GVMiV2CN?-qG}#H1swSc(pNX3;iVXCvI4?>)*DfS zEV3seBtMuF>wxGIMy@-ayROl<COU?po#35IS%xmDF-u_T4z$buEFDLZDmk;gh)bZ*n zpf&n)do@IW@&IX?NuQg)*A@@SyMbVk91#swl%U)4@XhBJ!ZlvhA;kZ=+g6cYBc*+> z^y+lB{_qs#z6ut)XBg?i5EYie=+3{G>qRdq9#Ce&W9$vkVH=TfcQj;n51uhHT3r;B zT6_T5-yMdKAG{V%q_{8RENKb7r0O8*`UsXjE&+_)Qxw__8`I@a2Af(c8AJicB2RNu zqfPB7#J#&NmPsnc`ve_$@dG|GTn>PFc6T@V!kkFC*{Lnv z{2zlvPGn3~;kqDmYK!MK2EC!+$j)?n7D;buK^tUm6#V9rocJx?4g7@SMLOyBwGL#} z&fUbl) zpG8j$<@{!{X(pae)zgqmEx$t2&u{nb;7pmEx3X@>ru&*r?f*n9#lLIVJQYTM+j;FSonzo>TRcG z+$d8}6=qVLNErQ!!D>oJ0LQwYNHmd>%2>+RAUWw{JIkEldJtjL&R+fWVR^0HBrepx zD`cJMgzU*{T#b}}zK?k;X_i!$bc5r;D;kTP7i$6uvL^4o8jguWe(PDCqIqbWm!w*99ptVNW6<07rM%RTEz-3dh4y8}Jujo-7g z6+`~{B!eu6AAP^WYTNt*%=ed!j-INqtx0IT1sBSiV(rR@e({fwyZ7IY-oCiG-KYpj zB-vxr;2NQ6LHwIVW2C_W!r15EX-C4m!zM|$2$n52&&@gmEJH52t;~*`M(`GsXO>4^ zqyGyh#+gxas9j1hxnOJqzz~mZ*)laedoaWSU!wpw!lz!gfqDOBA^*-~Xf6Bo@KEAZ zb;DzL#chBl1JUO1&XtP~c(KXfaraWE!*%Zu3T5`EiWva}e0#)@MM5kw=K3}J#@z#MEDJ?-PJ32H{wD2eQ^mYn zcpiwNk&C!EPXDW~e3Op)rbK6akxaMo(u%_RrtgF^$U5e}ZG!pW@6#0QV|XRjqxJ|yeg#m;a04UyUBc>sK2*E1at zy*_N^CkMT^9pXZL^_y6S>J3pONJIP5N3yP(51Y~}q6$r7jb*!3^Vk}mMSCSrc3kKn zFeYh{_HA0J)W!HDMcfUT$H+^VwsEIb7=-X>T9KgZ~uZ3ScV^y<3{ z7aE&?4FI5_wA7950tXXbR$3g7&K)uttv-G_=6HLmgk@dJh#@|c2*9o@-J>D1%If`9 zGy;sg+Ri!~=VvOf;27gHQ8TBm3(=EKo`e~oD8s|@rlZIPaY@qnr76a3F@&RMv6xGA z0sa8dBQ*p6MQ4uff=Lh@CZ=%NTk0pd*n&(glZIg?46TAU#Ekb`OfX=Alw-A0$^E;W z2Bl6wx#;+GMNS^+f)6|D9_hdsO({*bEaWZYovJc7^?8`dgmTMV$zMV#z66|Hax7G; zpuI<^5P*7EZsk;;cDAT~j($orqM)-A`II&-xNwZffr}rj@}2bmSRB*Az1oAeMe)zX znN@y2*}ensCZ`=@ofni--1T~lP6=AX*HUkA@`94E-OEqnd*B-@-p;v;XAbH)z+;;2 zneD!-ccu#bJ$x*Pzi9)fSuqcL3#M`h0Dw0%9ArX9zL8q)p5j@*rA7{z zHuO)GV*ej5-uf#F2733Mpi`wAL8M!{1`$wDx;sRaW{{E^KtO4P0h9*m8oFU<7*cX* z1cs6BuCw0nIp^MW?=O4pf8ev%^X&bs%`*cVW_|1HjH^QuS?(6?-;($nwT2!Ic7RZ; znJ9G561#0P#z}Lk$zX?+J@JetusH(6-yGox03J4)2j}Z&4TDbb@yFv=D=2$KR(VcN zj{aekDPX9v3jM}*E0T!9?;ijI06HmZkAbo;h@IZQ{t(8lRe|CsG8=sKt9mj9K+D&7 z1;*@F$f3%)Q$egX&SE9oYH|dNz(BgLTrIs8x<~Ylz#gTiM2!xr<*NH*sFI)cgY`X0 ziOmT^9+isk(JrbFhcXL)a?^EXh|plsrFMf5@P^iPSe@9N>Q8{-sWF-);!9lfp8^*! zFjEE25;eOy_wLiIR0vY%dY;UL$BH)u7Z%)!R`fnlG3QlgOCC2;%)_B(R0~H|jRV}i zKeOhSSApC&&P@q5wVzjMj>A^m%RBd}_|&p`?sKpKWoGT&XzzKI?3tQAFZA4*ZN8(kO_()s-jZ!VZ|`ev zY?*Vmn6V00rmxRAs1%1bs4KtqudjROzH(G!AD1*=UzNP3;|__|#$#nu`?4mx5N9v8 zv(HoS#O-1wC;>d{fMely!c{|Tj{q!bVH0vrL3D`=4X!C56W@Ws_3{*&V#K5DYSW9C z#C4X1eMdhgN8h!0yF{6_p~D$2m1FHJk`zpHDNZ0$ZWLC+IBxV2p(6&tUzV-;tjwJj zc0vtMV7*UZRAPC~5;@YHwWfaE-+vT6a@7i~ZtZ_b-bd!4i~i%Nfz)XM1n)OMqLH&yNrO`_&J(?TXGkfL^9Zbvq4XF^_tZyfN{7Kf109Y^k zvbpH1A*yBg6V^O@C#m>V|Ap7AwQb-*o40Rfh71-*$+t9P+IJ{iQtI?o*$E!C3 z%@A^n!zH-AIh`DPW1r!fiEV}RrsQLW4rpYTH-snn>h8$Q@t=>Gtoq81@h&y@?HT&! zD^yl6ne-?!p9`<+T~zh=-sfraWURpt!gq! zUR>^4eTx4N=l@^y-AFcpNgV)9xyio!iKZa!6Yo`GnSF&G1D3K%8gGqZH zd4X{*^glIR6nN_xQyucx{t1V4eR1nhhIpIhbK&@ZCLoAoT1eeDtskE0*@*86rzQZH z%{97*Qnhbf<8B@a1+K_*x2q6>J`>{&+|yms`LH?ZWbo=hNE(3~b;{LKHe6SLCy+2F zT{ChqkXCp#*#PLZFc(5ipVa_+6e_@Ki^~ZESsOF*=s8)a7A>NMY68IIyTI2V+9V(= z)uAq?c&gC=WV-Y^@O^L;Pm1s!*)vsb8Y!j08y?SsYaj=7LxLLF{bU-!IZrb1p>#*> z)8IY8o|Ph-I!t&0C`z>7er$e%O<$6RuWiWR{?RYN8pO!e#TP)_kp2D zxg-YnCNV$Z!+=Fttby8&2iCm&`k7w*dMRTLFp}NUt=1UEQD%}K2!HuQypXhOKP^39 z+oe>#P0p+8+OHXQz%65U^;WLpPKLE=w0;3Gl} z+RbBNFzcdn^KM(AWxPxO2xv6A!|=SCc=7{=lvIo6eAdX~fPJNMepbupm{Kq`+gvMQ zLZyd03;#3endCZUJSuh2io(&ZEVJB6mGDhVY1@@dTt3MdET!n9c3y6YYTYM}QWR*{ zVfIGstavT8>g~^c8a)O<0P%1hvyrUFDBYxeQ^(dtdc%U6@oud1dQ>$Pdc_(3z7Q$i z|CU=>zzjbKS=Ca9eT|WbGI+6X3$5XR zdc7PF|Fa?ASHHa8QN34S$u`@_x67LX!uFI?(~PTbbSb~ld^nbmPo?eb%M7D((v+$v zoG@kDm$x77%w#|_l?3+Do}iy$oJLD--4r3*u_02_4qC}&tM&PT(-Ol#q@(oH1vJ)w zZEoV1FCDSR+P5Z|u^Nawbko9bPm{#bxDoj>G*MG}y5HvUyWw@fx>m`;uLXBC7jtUQ zQ=@+SRi`M2y&7NQS$375jN9ra@omHL@v0i)#+bJXJOW_R-R#%qH*+W-|&m zxe5=_eE{Z^d6f^$26pO|0tX4Xk-!Zgb@pdcT1EgXqyY8GMP-`sjGp{9=V|(il^Xd2 zySa0bQx%Kdiq=RNG?sC|tQb(>UglF2&LLj%wjLh>^u3C1{bg`q&8vR1qhPwUZC0D( z@qSw}318o;R!n??>kn5NAoZ^pbz?#r?Ik{Ccb8apCSO*$I0@RpN;jBy^f82RNUzKU z*Na#GH#`WQA?CTCG*Ud>Gtc~uHkl%^z#f1W@~>}Z{@a--~A@rM_oEs)NuJ|TMLz{ zW}ni&6<9S#{Vij0%GL(4Ou61WC-2j)d6NU^Q9Jxq)4zLZ`E|-c>Gj0_jIT<3AXneQ z_*oMUb4R#5xx{b@rdP~OUI(ku{(G|`Q(5Wsp}&+g*h@^yIM};Scsw#txsGg6DF@}- zW`sN+j`>u2>?@(3(P2vDf%Tj@r>HHmj!KH_3D4mYZ>#5C{#4ZTY3Mm`kEFh^6ZLwYk=;yB?;I<9Tp0%nHJD^pZ~{(~&QR!67@9 z)^<^sT1j=Pv)+e1zr*9J>E8|oxzll;*}LHy!PgXNebcL-W3jR;+V*_}*j#fPAOT8m zgl?ErUjRA=jC?omH<`!a-|plwYJ`qrhh5uNjt+u;EnSb?3|kKaqwQLrAPByS*xZ%N zBL!%2d69GLzobSz!P0r-u~MB_)`yDooWPzx%*IbVZr$ElS&X}v9L2Rs9O!ahC$FMJ zXIxwVZx&!LlWH+Dh=)pOohtrq=10B18bELSXGljzk z>YA^K;1kx_u*bha<7QXuES8(%3iCt6)KlU$_9N2oLPu6|p07X@`Y2Bw|z z1*n`hOENkNxTfWTigA8+4`ybp-f|MR^UlFa+_{8X2yg}hM+?vnl^(c*% z+tZQT$tE3X^(naoi?AeJW&a<(YmvHk^0F7Zq7x5yEgc%_DU}HN>Q*&kMnnF1K^~YS zuPpc$1Owl1H$cIrbh|6EA6YV=Gp6emtFHg8heL}he8$awL`T35$aw|z5tGc z_#nye;&K_4GnPJL1Q9|>Q3-}L08qNf$6g%+yY*JIjr~XKG$Xx!2Yf3=%!n1LNmhIH z2hAjcL9CK5KUlbEBYj=ht3`lwg!TyccJs36S_^6~W`C>lrdRX#l_}dGQJ}2=nqAayv-Fb2Cg6Bu=JV2-g60WUkcgFJ;8niKQjug~L*I%)uv@k? z=5wG4Jf^({E=>$6p^w;sZU6Icm1O%$C2A|jNCZm8N{J#HsL^@|VQP0FiM(A-ODW&_ z!4c*|@l7M{?NY{$ga)bA7IVU>pU;UNEM%%_&5wUNjiZry_XV%-9RS;l#yoqHolPn3M#vO??e%|36^fUs+{ zMj|}V_b4|pDXMwS18~&WMF94hemX|#G{mSR>-U(<;r(6Tll11C?2e0NOCQ-Y{Gb!h zmU3qY>4RHrL86BANc{zQnb9wUiZ4jpD8m|RC#Tsqi=9*7s#T<%aeGJdL8VlP+JB^O zhKjJrief|6fQ%Azi`hK~Zwvf7Eae6Fbl38t<3tpClzxgRFn?L%nvH-4{J%x=z9J5r zK>@gwSUFn$d{XY6wBy|rv~||zO>kgI^5`@uq?JAY#j7P5hiHg>9%NOLTR-jnj;ta; zyD6yu$4P^66U0=d(B3mWt03;Dd8lakf#A^^*Q&v7X6 z2o6C;KxPt?Q}6l|6*S%=i28kY`bi!=r4|iTf7=IUs^_?Y7*4L`(kNf%@aA72^#4Il zg|_K5SamRyt_VNB|IrH)HA!=Xq_+cmOr%PDBEuL+-cy?q%n%cRi@!-6 zAKFxEC{Rqw!jOvbI{R`?WL!S`f$uTNgYL<^+RKVJc<#T>2lrgf``}LJvm=T&d?_k z^rtUc^;kS{lG@LCH|@IzfWvvSmkl2BV$9GWsPsNTiGc=YWMqRZug{A$;MkE{2rSh^ z{Mih+9=i&j4m#zobmAVnKeY@;SbS4zhmtC93iGyfQojrG34KmDh(G&Qj08HK_ra5*J@zm;{9PiY};XoEe!ZwJ)hM8}FH+ld1x4lF^oS zsUmjayV)s5nEhTp^qc4kzN%2U(( zlO^9P&k1KECN&jgGW?c3+D4SfE7VGvO`fKmtFj+d+W3~*v^$d#18ao}WLKDvuRMyd z2hjVRw!q|b!9B~&I3|U${+B?1g4;dg$CDS`cgMaK!n*T?fqx)OBvF-Nsy>Z6YlS_U z-{VB&QMXzZEST#*ShgR~JH88Y%>5Q&N02PGOmxEV;l6TmVfjd5vbMKi!cvi}h zY2N{BzaWvN1zLujf!|HUB)(4ZJP(9q?~hX>rAPuB0UF(ZASr<=^Tv@rm2 zt5>8Su^%~$ZQiM5SjCAI62=S=Z!Ow zET|PNZiG}z?X(*me{$Ii$d{cfLHCclbMp#?-_`tjw7QC~9xelD^cet2&WA0PZMUjA zm_YC$l<^_vBIO!alFzMZ?Zmd{5awjBzcM*R04Qe4kOB*5I@EhZRnF!P3=4?b5gyxl z;G@Sg10feB5?Z||>8Ttp%m4+iBrSEZ&Z)ubuuzOy*OZb$1xya07GCR=c0-yyQ?!^o z+8xPORXw!13}ToX7>njVecdg;sy^yTf>VG_8e!E5uqhS~V*$&H5g%$NFlySboEdNydxOhA_5HK&rLsZ~gItFpHYg z+E9tv2w@AAWgZSv+S?N?FyG`A47W%Z9v)8&a!qFQib9IoIXGtgI5+g#^?eLj_)Q`O#@flY8L;Y%Aiw%o1zav}bDum)TO4s;4YteZwD% zJ8q_*=F)U@CAZ`A8ipDn9*ZyBvh-hWX;yv~uvId=i@S*W;CZcFnFL=`}- zS}cr9YlQ69!#(lP(S%r{emcNq$)0Ml0^JU?tpklx;Jo5p7q*te<88FywZ#cMc0|%P zAu4JhRnPQK1G*jj%{joV(@C)Q>4ETx!kx~D2VKP%_tzXKcQeWQ+D9sGzwYx7iUo!H z&?QHF9T7Iu6TjMg&^wqt<*Gnij1+wo-zZRx;avu(RQVT>z2jsSD8?F-U z%|83rLM(=`$ivC?eT%}@a<8K7{#>=-B+zRsIzDLZ29@*Z4<&e04V0Z1+##GltT?HT zi2LK=6k4Va=_!oixLs)Uew#uT!7g%e@b0~~UPlTp#K>?W zxV4OavEYxD0$e#qf9BIZ!xy>A9P~E9RH^uGrH?1D(-%ediaHaXZpcwP1MdH+&Jz~B zNf)IaI8jf3PsJe>{%NK45Vj5?bUbf{V?_FMJbwLN-c4Gnd76JM4Dd91kan$s_UOo8 zv%q5ZL>EphBBmq=yQIk;?m+GJX<|=QEDcsq| z@`vh9XEkzc$|@A!Zp17F!K9Sk-^sL$@^l1deVL!Dmdo7ieU!AM7U;a*%j3YlNG_cZ ziCL_>`Ml4q)9COwq#nF6p;3P@b1D9)Ug@O;*HZ@DzKTuu&Bv?UQEag6T2r(@1e6y2 zM#dy2jjG#0qCp+^R}=Mk!?0b`L8@zckG`ph_wj;rX?y?Z&AemKuVlfFm7`ZInpBkL zti(>6QDEq^Z|OZ%uOm*PT^)4p>I+R>+WzdtMKb-;2(TYcPt!1m{?f;sav-xF*62eW zUn-eYL4PLAdh>b}Y&TaGfCfnGcjVpw*o=XZF7wG>Hqy7}RMK$yrC7vI_$w#@{_{V> zD3PmezeK?xe7>R}F|l`VY0NHjKcl$Es;dLGs{L?-XK7n0D*4`TNlUW5OPAeiOcg|3 zV2%Tt{4E7mQnJ)mQq)`J@7AZO#{L&DnPG*7*8z>W2Ys|fCRvQAxQ-!0FM1Z#F(QUnHu+Q5jm?R(y@uQd8 zOAoF@*{E(|rs$dt#bsez`B3BzPRH#5HXFIy!#x1ntE5CmR!Kl^w}OyN^xKGhPvj#Q z5d`NE*@k<&`7x>C%*1GD+1LVZ6*rhjX&x9R084L{iYuHal+>83zVk4^{8={kB;L(w zt(D{H2;hQGTZa49223mXc}3(4_2cuXwqv#I!TFM2;Zn7Pm>!k1YH%dLJeFk&iFX-d zd@TVW%HHrVp-Re$gUZ#E^SbduyYZ6jZF81tADUz)ga3d|_dxPG;DZE?7iy~&WZW<~ zvCn}925*^PKR*eH4@3H~vm6FXa|i)woBd^n4b8V}d?yR(yMWi615j#Z$@3-%_v&-u zSY^?GIOQWRMS->CqnEAY74@RjBpBse=jG#~<0=grr=`E`oOs%ynrZUv&IxKXm&$J+ zd-Q;?1ik)GWS1S39qRWnvI(lm=&07ETNSz8Fq-X$f+LDa@i|>x7r@`}m>o7t1c1-i z{KV$TLVRiK3wbq9r>OF6{iZhLtB&;pTH9#udb?mko)0jL1^;Whl^3JQ9X-F{mC_Kr zOfFNyGPC`2>7BBZi6M*glFu_gvA+{FEYj~WmK_Nd_gitce_rFdNXhSY%OYN`UMgaO z?Ed0=JR*G}^$ooEBuezd$UDwqQ&z*TANu+2PCw74eBvcptameSMe3NsNc2VU+0c3pFKbwYoirEUEMpQ}umMJ$r ziC^6ch+P^%F^n7)kG)XDaBybWT<+l#kLCzqyr&z6^~oztD)c}X4xK|AwaPaWUQ@o? zwZ=LwW08BFva7PfnSWIULix*^T(~|+Q;rQE8NJ8iioiZm&b3*duD?~>CKmM1@o-E$ zx#+|dkQ7Y4Lyqct@8`JYlX5yFDGPU_ zq{?coB5I{drw9nMyIX{T(1+e{rL7mcK3}Jv@DS@~KW%c!zn)6W2PAZ-UnI7BjvC9o z#&17_WJc@{8Op9k+#;Eo$HCMFmB#$NGt5Bqq_S4B>tKIC-T;&OzB%)Zw{41(5Pdxo ziK7=VXF|ui&6o-?!_Gf@sIZFfB$`3$>=#!QVMK)1aso$f2ah;4oP;;PW?)mN!N`o- z`l00RDKSV4}7o8_Z zwp`MLb((aaTfzy0fx3VTfgqAttDvengl3x0*`C!D!ymH_>G(;-Wt`d0?Mrah%` z{$5uJO`>nt%a)z$4;c=*Op>6Ct|m9|W%vH1HJ45!rBs19Fqo^A6K=gJ+xzsu)oH-3(SQeWw2qy2a>R6|@}fbbq+VqriuV5myx>j{cS9~(1s<2YMU zFWsoTI#1-TS03rU7UHh-wkD|lh(jFl)t=Af%mLSN0}*4^Cnrp*MMC@!@!38Hw2-G} z&W(7zzf9Bq&u%MB(C3Y``_Z6IZM|gsO3>B~DUY+QS#RaZj)Qz>?$z?mzBEs6GN%A#PbCJ>lT-0GJXe;zIKZC}c%79Lmj?djc*|m2lQDZQv$HK){gTh~qQ~SG6?eB_lsB zK|yQFE?^}WOiI94r9Uof^`h)wwpE!Ie>Pz(%e;D3FfH8{Ua%aP%+50V^kr3c&?mS4wvHjWj9RQOT5d*YR_Hlccf6GXc1x$!i!z>0+#_s1ENJD} z$nd__onyrRN@(YfXP>m<>j=zE*Tr~M*z)BJ>Jxq&uaY9`&_;vUo%$UXY_nSXy^J4y zq`cCqYAipt*ktUeCB)<|aybV>0R@|z1`GQ3JD>KSe_}x45PWBeExag0CPf-V+MeUq zWBVn=?AXR>hg_z*!*}5?&0q{gIG?*_q@kR|2Ko>Z+O6BNc^XM288E4~r$@AsQ`w+k z2?dyP2}{+ef+3`=J*zxd#7Nrwpd2oARlf<3c!D+<-@r@e|7>V)SQPBdD|jft9h?tX zUg6+CKtYKf)aoBaxsE|CQE_ot-6cP-0%gu&b(tjBw6G`W5?#aV`6!WZEj+UhE?Ed$ zW_!3?RzK}`H1OIQ%!HcDh;?0yz@^;_8IERJ{bUdYUiVuw;`#cAZCR@ds3+O zLc*jjoB+m@l||1vP4vg?(eZil=A~wpTygfVeTM@f+WjU};Arwy3$8Wx=UVH{0@4NW z5kAWCpdLvNO3#<(nr6V=^qc19C*aq8FoXUJ@avA3+DXtQqD0)~5< zS6y8oAR|-XzgT(oow2Df{jG}y#Q!%@wqP-I^r-FgmYfOBX*|3ewg?zlpQ!yLO1kbG zZ%Eg&Kshu2sEAv}& zrPVei?#~I&m_6#`=dpi*Y!>(bwAa3@mQOQ%XYqMq9zyR!%wPn(V~8|H4ihNw^oy}S;tyrky))|MrJc+<2hQUxkk+yF z=hEKj6;$c`+^aZd1J_c1*y#6_IUFwR*ta~{AfSx0&cPIA-rF0?6xpT* zWWEXuu0zAY6Gn^iPD?G?fN1m>kM6ZA=arLZ8D4MU-;P*S|Hm|^baor9MjfI8+*xeh z22-`pHLRyI<)*&}mXf7$H4BN^ay7_%8>y8BP;*D7!HNrVrLtAy5UDRr_C0OK_=d^< z5;!HNvW6dfQ6fzmbu#i^;C{<{-u5pyYO)C{FEf(i5psO=#19{*SLU~xMPkMMoaW>^ z2@3{Wl#X|?i6@Cog*kFw%C)#Mw$6WUiTR>7pm1uYbztc(H>I_!#5UAH>7(Gvq5FVx z%R7U4c75{eXH&yKR80we_FF$8e7i>n=iYDoaw#B=rVB~6E=wk3Ba)Qkhj=Fz*?G86 z;9?>Hf2wMh>aS(=N3$$%617?k7aCr-z0=s}jY?_kQ2F#$_d{t2@4z4<^oB`dXwraYMb5eV1q0pFhNKmvwCdFecNwQq z<}qwnlo*_Pec5q~0Mtu>P5jE#9*y@>MVPX5|5PP+1>YjeyJNj!d*1Hf{Q8=q zMUut+4;r%O+p1%a)w6(Rr-v$XWd(&ypTP4b?C%wy^~wSk3s29VEBJ0f1DD&MN;_9H zEv_RvvMjED(EL-J_Q~3-XgN^tIH|ahXJ5ZC8V(xkxmjqZLXNdwA$lfPv3a)A7G(fx zy%8d-Ifb}tkde?w|9n95ohZ@jo5bh&vtz!cIr!v5!Mp&HRg`$=ulm8nGt+Issj?7i zT^v>|3i;|lC2}Xl01npIqn4%O+Tl`heD&>sAFu`kKRb>rE8JD@EF{k%TUj7(?y1#E zG7|DpFPDo2_toHnqcS7;Ufo?m%ufERH0x|)7;pvqg-NGrZ{B3#Cmz#_WgOY!QKqwc>0{Br;P?2Djs`4j3V#g%^YYCV*tdpw)e*;$< z*q_d8XeDi0dyceq`sHn)rE7)b_{mwbt)Ca4Q+$9c7MQ~&BNaED$`k5wYQRcK@Jisl zm5k@B00y-lz{1p+gVMqW@c6*bXcV2}5(1$NAHGSNc6fCcyEuH)Cb(LHf8OT{bAPAf zrdvTsF?iKnrz2LH?!Xm0NSvzNuFV>E0w!)eOtY1C6-DSM<2JvD#fYvxw)(aBdn1e) zTMbU(ax{WP1bjANqHk?@qZ}BU6j1$T)L2wZk@9|-EN6iN89;e}O;xPg z&APP-mqbLMtZsBH|ITFB6>&+RlCzXbEV!irwumcj;pKK53Apz1KaXl&^&Ut@u=}2GYu%+OC=w8{EkI5`McaTtiGB< zG(cU$sDpF5xQ~T3(RM!EWPCn~>$4N}ds&1{@r`RNWy)zAeB)KwCf{06`slR4nWzVa z!;zEVm{$)D^(5auL6Nr*q$n`&#RoniZ|!i}pldViEs`bZ1;5nQ3rtFHp9Ep}!Mh!J z-hY-n-)?AM)BAqyymof`6Qt#M%iyZNMoyHqT{r4Iv++&*LY&d!?Z0ND+w1@hGk+6l zV=0$n1!6P6cPUFgkACU7*Yro=Y3Ll7X5Xof9ZWcwI{wgaQW<$~a_HsMXr%hu4 z^LGjcTJ`z)y;^DOuWr?*OU6=Vkp0YAA=k6!K{5R&_0DN>g@?b;i$9(ZnOtooY8LZ< z%NaS&eR55V@LTdUbbR`Pu;H_J*Hr7Eq$|VfAcf_ z1mVbM9<)>bDGBBAwsOVgZ;l_c);?D4CgqZM{b1|3wPM&_bJ^eP8>rFM?;HDI?$Aws z+jaG%&vjpKp~6wZY5K|NOiF0Xr>$cul>Uj;^}NDE2M(j8>UjwAF9i*Mk)P4sutV0m zo$TUm4NC!rylgyWBDOL4^yJGdi$BuxbzI6Zxu+CNqUOWM>y%ata{8=-J?P0;#cQnG zL$2cVfzPLu{|4BkY2ck_sKCQ|3~%|0#aqNd z4^(5barsQ`hbdV}OiMqvvhFcyTPHymaK+vcTd9>qsr^{x4w3fzEz9=&`s<18g|y52 zI?J|acN@QUcs?q;jnWC+`82!V?`I~vg!0~>vqyohEA4OLmt@~*mGVv zD9tr_?U{tqmA-QxTHM3GH&Otz?37D6H<6?wGCVdKacPfW%tfk!s-<VXCEg$au_Ks-2u0f4IaU(ufpz9o*Zzb>6W2E~SK z7jjV5bhzBJecB<^>^NV8;ps0*y@EB7j7o-O`E?nVQ*Syh%NRK5AHf%Uzp$(ho%o?J z{>28?eSt6s)`*j!ZC6&lqB&o^>CsVsCtS913J4E_OR$_(*z_-S^L8VI8Od=6V~h0? zX{;*|8Vxg{eI04Tu;ak@A%ndJq@FZLWOg6_KKX*v;!+Bq z>zlpWt%AGAicM5Yn2RJ-N9dEKQ=GJyEfuYd6%P_fPnW&8LvUd&UN(d=R4-VKwm-8X zcC*R%iE(#3_rLuCAagbi1WC36=#;nSn>aFr>@#zo-*t!JB*nv2=flo9nCsQ8rQbAp z(&_e)HYH_{8}4ZcfvhCB;+zwypC8I!`LQH$c%T>Y8tdw6&Kp4bcmEhm>1Y2)Y@Aaw zmaodV1C17c3oBTxi}3yh1~A4|KlV!y^!W|X1$;byaQUGGxryBicYs)3C$&FI?k9HG zH&~qDgjsEZZK8cXK7tJ&!UIuJz>nZfic(dkAYtk5}h_S%IS-!u1o$ZUT6;Pndm<;z$7DWorXJkj>NK2pdp z`sC`knzVUa-k8*dcARf!kTiIR%Rqa~&_R=cNLqLYN2d~Q;}-)5plu>@4+ZqWP(;q^~3N7+&nK;H=NIf_Him>gkharFU zYwylaLxSw<1OqgDZG(yK;%Z)HYO+(aiRYTn2_9z|M$x4z@Nx(fozo16q>BUI%gDjb znQ}T@+jla5>0c#YwUsQ!$tfT7I|y|obwsBen>7yGYOeTZYXHs6ABHL?K>4_2j=`?} zSH#V}naTGjEh$@yrzvshmqjPbS2C_O^p_*9L9_7<&m2Zm+AncKd|l~|t7VOG0Ra3W zDX4;+v7IkZW+DD(`6}T=_*?{!YeYfVw}g|-hhxQzTcf(6Y@(bPx=Giovsv=y+q;ay zjwZHJk()H|jm%i$ofLq!A)Fuj$%pTR)#Dm}<-tP1Ehu+KV=nMC(J}mUg*5fuwa@0N zYv7&wr$neeGx%jNO2;zJ@ z06?OE(YU8Zb2*tp?t#sSt^E3L%2N1FglNLo@UFTqsbhJ(%qWG^L#4nt>_09NUr92b zc{Ug{UbX`ikG?#%Vsf-%r5sOmE{iSQg|o+T1IW@0ivurIVwGW!x5evswCO=YxD=&} z1u!akFhN!2QvnBEfPo!9k(ID4n`Ut=VHsU$Sou_Gt7Q0e2#678v@mKwWRw(XP(&oX zS2|^B&c#`$yz!ef$_&ZAXXR!vw=JDjI68O^*}|J+@-TzC(+BPdZYOwHf%sLp4NrtT zX`Rf_QM0t*b6hE4B6I9 ziY&tOl+R}HOfB*+-(fa(K|Hae)v|8>=!tb8g)Y54efZf-NDjV@^6(%-wi{ zj@rb&Fj^sh?MUqSG^hv9wc#kZ?0VGtWZDM&2crGWqgbgPP4uKy}?|QX0phnK|9hv zz~$_>jqUIGFO!?9r168w!@j}DB7Zt1C)Kx-D#lLPQphOMZ_1|MiBXP>bL}QVw04}n zUEeddL_g4ngOrV1k@xig!}MxMcib?q=_W$T-u*Q|-ohy&q>bXn5&P@|qjKg)1&3*Q z4{T=q{SiyYZ{YwfVxyU@KsQ~JI*0t}0p!X^$$~~5x$yM7?BLvhEEU~f&t;D!Zri`jL+F-}_D!KM~=z5NvYf6?L-o8d14c$bM;<|mh=A;@$ZM62_{^MNx^ zjD*dRj05K)@6jRk*6Kr8dW*!0f7^~mM%m^xoz{s)hBQCF{L%XbDN(^1qu!{v&&+)a zSfeWFPplEDT8S8+OO$#hQ}na*;LM4Uv^}PBJ!I!4m4w_?GCMO2X>n?WC7ds?ANF7d zoXy#1Wj*JnK0XUe1{x6o?PRj3M$@RKeu2v4zS31`Ew_NYf)$d$_ z`1%=8#ms=);cr;ez)awwAW z+l~tb5dgE<)fHP{?fom?s|gx~4zeF)@9r}HT^+WpTyq*9IVUKi8I4Pqe#qYz&dvK< zo!JI4zZ8B>7FGvdc=&jBH7e0z;62=y^#eRHZV_~9WMgutqDS_hAM{10;?WEX+{2`$1-za(70 zOz{Z8@B#R#A;6Iim0S@Ohqw6HZ#Iy*jm&@XcC0oU_Y;_dWEDP68+v_}!qP z=5_Zv)gzv;3d*%;i3?61gN&@+Co(vj#*&~z@LSbeRc4!{yCM_dSP`rWQNW0U!}GrH zWSFjoG=f{k4#UW2!&(5%bXkK1lsU}a*Mcia!fZ1XqdAeBw!rc9oQ=x1qmiv2Q7fys zd_&3nR0HPl8MV8Xz;00?~$;a8v03zZ%L9w&?11v>lm4Ed9kpzRJih4ub-@#V);FB~_Wy4SVgxDq$L zvftrHZgU>4>KDrw#NhG0>i4mXo$NYkfaBet9`7q%Rw5Dz@nXO%{jVG6oY4nyV-O?Y%3%8(+&%69ZuIxD?;l{W+D0$Pa<@+%gXH zx$nl)&~y1xLZ&YEevYF|=VQVL`oU{Pn?1&RuAcSFRo9KbDy39Q%c?Zx&PaMOWsMd^ z!%3w1(nsFi&JBh84mkr9cX!o{mGmN*z-E8T0Fp6=p-b*{PD_uWi$9zfHy^bD*eb)o z6zYF@xLQGXl^5-$Us&bbl)1geC6=KJ@eQAXO4^?at_pJ@*R`{lLf2$5WWHrd70STd zp08b6+_0?F356?FMLS}o`N=@@X^CO09mOop-YQTYS*K~7#DCpAY zbYT5wD9c!Tf35%~RWpv7i)gh_RY9J~(b_5pyUdOgs}lVjAEDNHQwI8xOMuC_ZM#@8bgU-f2D(F}>Rl;e zVzkLTakq^F4X`8tV>URxf7?WngI8VK^2o^I1}e+kxDaR{M10w0KT1)uhi0*}Y0>l8 zNT}_C2b67eF`M)!e;IZ_pzx^AX!oquZ4`09rkzhMfR}4%y2Y0`kl~^wEk#{GtUbUs zta{YGWt@xQ0iPBZn&XdyrdI)`k~-&V(6MSWgWXo^tR~Q?`Clhs`P&AnDaZ?}$A^m9 zy3Sovm8c6Hu`g z;Z=u1d(ChiAmDwVwDd7+LZ--lErxJAFTiV5=AQE$GcKVHvnmVZq+?$_T&N-H5qDk?1~0@5HK zLXnnkkdPW79UCHoqRgPAyJ3v(O%W!obdMfgBbWE<`{4KB{wvP8Ugv$T^S3TI218I= zKSoAfJ=&nyi(Pg&$b=@XeT`>u299JuGG%n8eq}2{ILu^QSj)T;^_e48a+DCi*ZZp_ zNaE-j*~Ph+B;813B^NK{CwrJwk>^dwq#(T9i+!bMxVeGW6uB>Y_6 zG}4W6>*w#A8?0`R_XF3@A=MlFTVY!!03`9+ejbJ(C<^U)5FElY~|SKHERS6@#_gOC)ptDAWS7}C_VH{kNa4uuKYBj)0C;RuuK zju50EPDeGcc}xM6O)yeri_njL1Yvzc-UD~CHpUqJzU20Vq!W%sHVJ>i2UbXvNJ@1e z04cH04^crWt>YNFI^D*j2xq}v_mB(pu7L0fc376oJq_7wbFpS7D&C7MH5>B z5Kw6QdD!JikuJL?Y)hn$OIX@BJ=0Fc)Jf#b8;qj|9oRAHR}{%7^A@GX@;@Rjif@TGAbP2$U1J5B2WXRD&n zx@;O~p-jV0N)1yGqJYNkKLytchHJurMhi`#)hehF=#_##ubtuM6{mXvS~8W!kBS@R zjLT0&NH0G|DV;!1eg%f^JrTQK6*$Jy+)dL?KcQ{-GCv$@g=hQ1=+i`MOx9LZpuhhw z8P%$~qiYMdcy1Rb+tb!>u_UjLU>vHbST&BTG=ysJG_}0#Dler1RFJ4QO~#w)OAF4m zr5HFKRsK7U#WlhwV|V6JhpBJvTrH-|jWyfQMf}#^KNl{cDmRic(Pz99w&)xEM}DyVTS2 z4sY^h$-jOZD-Oj3yp-~EV)DJw%3npCSzqx5W8CwfV_fK%-(c#48#vNy>X#SAeQjH66rA zkW9{9WwUR7d>2oA65Gp_9xWL%nYzkjw&fT(4ra)GFsVxP0-pFa_}Bg-$`ts6!5s6aiRdpEzML`XYz6 zp(7+XjPKaXG#Trj8ofef&na6t{{wv!$ZwfsB09=2YYew*x?|v%l_u{S_1pD>+K0AIuRC`>W~7CC3ZPMnX)x%)atEs)_XUSUezMWnFCGG zsL75_P>FePhP-ck(0{U&zsR9`jn~49T}}RGG`bJ>*gTOjN#dMSbv(+HcTK(>^8VM= zEn_N_!|9E-{BZ5_^9;AucG|tX^261j3H4B0lCstSCLDx{obVH7BFL#fYf9k7})rb$RQ>RL#G|fMi z;5yra_`u4cAv^lx#f|1|QgHIs*|r&^;E~1Jxge5zIdgJj4Gjw-58|g=kT}w56F90N zBr2K23y#XEsl|CkHbb^ncrnyRb!v_nk(#yrS{z8MLlt044!B58 zqn=|m+MDL6?@j-1ikT(J47rF_tCo)(xjt8|q$YkU+-x14yXHk`5m(;}l73m;WrncG zJ1>Qi*NB~J#DHF#vv32TU1|%L!X#Grqn68t$MmAVmAa{;!*A#0dAwEihFguY8bWXW zx~}2~>5i$wEl6e^;d0CPP^3m95;mbp-=1=Du)958s^qaZ zR>FF^{%F65gppGA$d{PMTKXa{`c(dQ#K_ScnG8^9X2Yh@0%(uUMakXqxlYqm5$Qn1 z9XpfHkiN*|wYex`h3-HVcHGtEH1VbSh@v`4s|}wi$l?vtT*`YzbJQ`B%ZJ?D`a4Se zGJg;4VNf$4nQN;31LGL}Z}73gXb2LkcvO&JSq6?FL~eJew-(BGbLYXMhpRf7+dh0a zG~WBo*s-Hk%N`*;3LGMZ+v2O>YuFfPwOqAmFTSKlJDu<-?Ub*U(YbGSLadM$`*!NN zTl#$u-GrKvWH@HW#BBPEac#FwWly&aSxj<>eAf6Zc@i(*wtGNeNt*9$tr$hb4Mz!1 zd#rxn4}eq1X?08eEG{E?l|*$#LDWy1n)U3QxO1#0JiVS=Q5 z+PnD?^GAOVXImm}etcUoOe=@hr%VNE=VLev3k1|d1yNnb`#RxJZ_$lr#;vAn8Nlp| zaz4=(;JWoNlPL309WFqLeBRMi5NhiP5vik+k;@Sp!PbK6RMY3}vJ) zqF$1wXS!6aV?Cp;|eI3ddxSB>bx|Cpx?T90~=VfhR>BFBjN<%J{=~edRu$Lm-x?Y{)tV9B6CXev#Y3?`#^)Y;9mHR!~CEZxDhDnWddD(jW> zaE7ZI4M^IqPA~e=$eJ`C-|3>|8myI`chh%UXZBG`vtjDTFfCuh9Qo+v!26@-e2?1% z1H6_yQ8<&LrkRA3U6Mr1WwdQ;s23R{!TBIK`@RHNvf5)f+g!>Hm?=oF4E9-+fJV)_ zQN+#yvosD^4hNHP&CSj4Nv+uHv#nK9vA-u`FUkqDy$n_&C za}bSUEp6$#V&0YlM`+E}yV>I33v59w(b#AX7cf_%vX=3sh^1rI!VgpbbFTy@+fnrk zNp-$*jG*=koV4RTW>nkuAbQI+uQ~_Y&g*xKQLH7eeit;54m${OtQ85;8ci zYU|s#vxUd8iTE{Cb_Ipkc91u<<|yNNm+VcmG~4Rbm`Fh+_?`#m_&i+Gt6R7W*L4VQ zio`shp2<5Q9)L+Y?U31zYHLTm(yetd7~e2 z-N}v^R!7Ro%~ut2=>5=HR*0QhA(Fxhk?z_GziD%&&37RRrBkbgO+3Kh`_j8^2wqYq z!9=8u@@5QRg4CZE-7dcr7>+#cMH-4oJIr`Q0^?zgg6NVQd}ey$I86LJOk=__+#&d% zzS~N3i6M}8Ew9rt2s<=o7ck}=M01?YNz(OF7$KnR^-70^g;M#GD*AoMgw?$v_<1x8#r^zr%CR-6YA|W#oE!!Sfox z!3X^XZZb(7X}OEVU*QD1Pl89Eg*&KX_heOQ%cmDFqzqW$4raXUD*13&5#L29X?5w; zC^HY&8C|@Fy{v>y!=jH!+r83JwS;5r^x~U8XL0+m3HYZnp7F9033xmHOZeuhV@w;I z`G2)%m}qk(pJ1V51P97`HtLjoC#G&|LwnvaX#dRXdsCCVbqxf&djm~361jKU{$OKQ zGGNBCE#uH#zt@OwBcucq6SL2pzz3By49yh1Pg#5Wh18gOp2fy-#xlB z;`t;TdM5jH$I&MrElPJpuetn?U5jR+oDaqPof=XC5||ekDoDWHJcxXK3&OS`5K?X> zm@xSe5STqtTD}dXn_l$q(qQs36!UW9^`3WA{p7JUcl*x(Rj?3n`T7yn(ZiR@db#MX z5w}6A%j!q2>ez3bGdpRk%v-=W?zHn;5S|GaPKHw4wZ$c{LKF`g@8e)|8DbW`XLcfu5JTk`cha1vl;^ zA8Fi4`C496!G2c842*g&Fvsyv zT^6^d?;0k#amMYY_m_I=e<&T8cPR|Agf4Z)U+)l=LNlP$ZNp8`^bcAFEt>6{|Khts z6FACD(-R*IKB8A>H-8JV zrE=dz`mN`ba3W^+{gn$6du$nS*URidHGq~Fzs$X0(&gEm^icFrz$W$HCFI26;{@^l;bCCNAcIpM zaBTp-qkw|p8&EX&WYeYre{{{8Er9#nS_LZDUX?HAjh$$#r}3=I&EFh-TbJL(Z@2Hl zD>i!EYXkDieH6B$`viR7Dy2slX3X3%ua?X)$~X-A2cLZnjVRPB&Ak}3h={AMHi-hK zbp<)Rq%zJ?hs1KWz0a6DHn~4eTfT$9b>nL1smo|$Y0ews&>X#RHeq{+ne@2 zxm9fa(Y9HKMHoPrGdC3&tZud&6R4DO9)bcVW)kKN)LZ`s-OK+8P_?PNhPI}1;$?Y)u40U|d1UA5 zJ!!r5#3ueo!8L4_61LPJi)L23CYl_p9$~Z?6CAP~On_(|eWtq&kHpQh?qY;f^Db2` zvKtoiq9^mheonQ*&v(1@O5h{}R`nuWTG@xl@+!uKh*rUgB<#T|xhEx(Y4V7t9^Ntt zGBG@+;~+vx;3`Z~fM<(z4J|_FA5EaFpMcBe4?C5+i~{DSNz8TW(HU_#Y}bA!?uthm zwF~!B+p41A!rHCYDlV`oQWE2Y%)IP4GV4-m1~~Z*5f&}Fd>~l)KtYT)D7?Xi-=B$i za_3$9=$Z=ROGV~RxhHQ<+}#94=qZeo-6lUqe`U64I6Iff!g za)_AKci4J}<{O_rrd&xlp3YPt9Zb7@z@u`zDnP8(?PJ+pvU~oTM;&Pza~58%rmoAd z41WeBPGLx-H@o|x%wgoP_6dm4g?jX`V+q;l*M&Oj9a$l&7;q$NeM8|7*;-xLjp{Q) zE0EwJ2IVawHi24$tA%>&8tZmb8ik}D%J>V|#Ik9K9;JKVWdoYeR?-Q+7);R}A5i<* zMXcs8xs9TyXCfX^MWSF6uTGU&ry7>nw_K`T*{16}Fzs>2)@}gR6kW9L{lNfOY?1g@ zU>2~Z*}+^9Bq~TR;k2JFm8MwA`O0D~{>II)r(JhK{j8L2+vt3H-_Bh@XacK(Yyk{_ zNi{`5X>`M*G)kl9O!j+I*l6{e$@3J(WleiyuF&th-0=kit9)oE-=2AeIu>10I#6_L zBL#mWzZup!0NN2R(`*Xa=74TZ5k?NHf!ey6O!gVN8V z^7sd?;2qwfnd(8M&f@#)QH`8-LKt}zm-3nKd`oL|VkDR49!FyXej;Cu>j6OggNfv{ z$hJr?2DhlM*QJmtYz6VAm(!ymrKO}OwZb}zO?%cd|geKv!heDpTVmxRi> z{IIfXiOKnSn_y^R2aC(l3WN(P}VDY-k?cUTT|rrH0A+- zC}N6S%2vCofZclT{#Vy|(ZP$=j`}{m->Q>_-zy2Nrk}#QQ>DSX0toh-;;%oV3qSd* z(>EPx_P!V)4M#n+e*Su5k5yGqz;**y!*L-z32q*=w8QwXjWWlb73?2{8;pUH#LP;? z6b=`>B>#NXpai@a>4BWC@rN!{cQ1Kycevqn&>$8j=fO_YnI>>BQq((${HpIzN2~yH zoHU<<4xLXkc)*B$<+v;xvLY~z*Q6O-byx*?ywxq~>pE-Zoz#&seG9GtJaUETWQyoL zpH-!Z8O|r$>8v6shnpI&)m8{wEZW)3hFDz z^rv_7(|?M5JMam_<5rh*t@5aU`u@(+oiL+nC8Jg~5Arfz#*P$14!_wB?*ZQ4$+|h_ zFIsET$Q*=U{hn4#Y2TxJeX&$N>eQ{CM#vLcA!B(iqpp6Ole|UY$kG2|Ojach#0QAc z>sKA3&_Ra0`a2^Ef(h`KN|`qT>m-x};2`cx{~m)D0rT5QE^Q7xL)vg8uJEpEz{=a0 z)Znfa%Ubon?1SSsk*iI*pM(YaaQE&Cy?~81UJQulzW|qbzklD% zpSXI25QoP86?u@2k)Yc_t-Zy$xG~z5Tgsf*ip>9Wm%iF?+?G9<5!hIyZn9>z+m5`q zXr4|=nBY$kuY{F=!h`}?Rj8ECEIwW2P_>phz{*G_Y%%xahLyAf4o}?UCC~rHnV(FkS73l1GL6)Q`Sh4i6aMFXjXxqioF%V)M#|GtxbC`2FNkfPfyw7yI_P+HndXUUGu`q{CvI(r{w*9+dKe6#O&&eO&BB`9TqgYWwCT3Lpw z6M|;5`M1Khes=u4=VXJ{*5(d>Ohebt&X7MrqB8Dhos-DlBBm>`_}{2Yyumnc5$B>& z8AB!aBr)COJ%fFXTV|+_7rNmDA zb{WO^#<=_*U1vjk8>qA3Nb6X#yx=LoJ35!)fm!xt)&-5?8JH?0)&=WT^Rj0tJ-YG` z(RS;rqe9?oC3waB+lVi$At^X&Dhg9t4M?Z!bEL7Yn`Vd13cAZV9wrhDfNzcZ(Kkin=~a|KhKJ*$E7(=?nYR+g)^ z{(HTx?EA~P4vE2#jbpAT7~+=yH>;#xww{{RGQJrl_T3pZaB4}zO-A~4MBVxlA!enQ zUa?d*L-jON<^6tmFNjInClPW933mpr#k}1?VML@HzNryr;eQ^5KW|@o?>!!hBphz5 zZEP?nT|Qw!45+*>k=OA5=2Io&#q#PO)e-E(Rl6&2BXIP4qeT7_G*~jk$plnMw0csn z%`on3%1f2X!#gu9EAT{`?OV`|s+NVo=v!4d&@Y7UX8c%ccH?+iB|P%;#-C7r+^T_s zJvQc6S@&%HhRLXe>)Bz&TLfcD*7Vwp#aL$6DG!b{=$b;{&`e|w@HYHZFpI5ZJ!iL zGkGWSuuDI@O2l))556f2cytA|b@};WZeDS|t*^ZEH+#?>M!L(_Q=Q|r&njx zxuQLztH7*{{Rs5U=eB_^WA2#S5YMxnMMxu$WAjppRsY#2!!kaQ?=@wi`;2fQ$`!fu zFyr!2B4(Dtc*|&_r5m!ltDbRA$r_C+{8;8mfkC!RtN5hb|7-3h4UMj&)kux^3SQOV zUkjZT5yRE~5P+W8kzC)@gMWQSq+=5wQwwFr(;zaFH->0?s8S3u0kAd`NxixxyMW?L z<`Pe%4#eVg6Uucow-&lgT2Pqhcjk>eB-V<=tfL{~9uaLqnu z_urT^Y4q4yPxI5XU|wL+{efs*0w3+-E?$Jnspqoj(_!~2oEFw_r+E%Z&gfdBJ3FM4 zCQ(ga=uBRC9>?F{H{a8DDA2xVP7EU58QHENd!3sf-8XA_Tqx69CboO~!0NOzw<(u&Yl&LDAYPe|ln^ zp!;bxFKIcPZZC3kl}Dgh7yi_7aqjxZN~O5(ea9_=e8c`4Oo>YsNb?m?390N+)j-RG-MLH;pnR4yBqJ~u7K z3RqZ-*LS1bGZ$e4@{Vc=mDm z`LzXYzvbu5op7^VK~Mvh|IKCjG=a}Qc8{UH}+XgtnOipi?p z(`4>)E22kyS=yg7@%e&vFE=w5!uz;T$8z2k!uaPup23)M$=L2@!87r8mFP4fxO%kvhtoU#jz>YFcIec=%VW*Z_=h z)WiDRzN7Eq&u#&)lsU?7g_ayW|Kasb>nq+-;gjJv&A;5ifqS5b>L>q<%JdybnQ!L# zLyHATTY*PPmNxveFFM*m@0s-T_>jGLXOL6F(kmK^9`rQc5j>a)(Q= zH{=k8$(Yw~5#!VXI1s&yddlg{h;9}pgkbRg$f_7T-`*d@Z8273YU!%U{L14t%y+3O z95ge0Y1O@_cJ{M!qBtVbkqcigRZ1@;Z82iI%2=Yx82JY{QkY__3VTVuNLWmhdW*7c zlKz`!mGvmNlZBsqZo9pPSs@5apA#}y;Umpgh-P$wacyQXjLk7Y?A|1K#-SU}DP3jV!tz*+ z@DgB2vK|bO+#QYOW3@s=^$rNo*PL8bobGT+Cx~&u*o=%`MtX?a=V{erxpw|S6mQo1 z{3ji=G01ES^5gG@`^ zrtX5J>nhKqX;Y}e0Q)A6nC{i|QSZa)*`3YfQ>!__-391>rY|5HjPRr_)U)Fy_c%3+IDZ8|ry|EkJk=*C^8Ahn}kSBs>x@JnY1 z)5hs2U@JPJyY$bV$Wm#eL2W~mS_X^RmVg^2c1WRX9;b&s)OY@TqNcU7M1pYt=KoF7 zY>pT?&P40yF)UY-MZa2?Lpcc=o7g3`^f1-!Vr^C9OVJIQ_9>3zIKIOs+!Q~>IB}j5 zW#fn}8it)3`DR~?lNITrqiukj9p5MKCp@uWs_&+1Q)4Pd4v^fM#x9?EQ8Gc7p_n2L z=Fk)ZL37CQUM}qTLNmPc8`YB!lb<;zxc|xA`RvC*)CMlxr8#={wTTZkqXFXt=m3X$ z{>dso(EA*j#k3d(P}7lNZ;f?f$OmZ5{9Af3)28c%*av|+sGrtl#_#ggO-i&$ATHnJ z+WHunh>5EUS0Vr^!c49?<2QSqSUakJ3QKC4ES|8bYowm!y6k`QvM{FJ(&ee4pF$Q@ z56pYs+XYsvC^5VK>FTh(`WUMOpgPwS^X#o6Q|SP#jVs>=%Aus?iwe@T18#+ki~a;8 zqi#{%;OCvp2@=>{nBc6-3F5T zGr@f~GOKQc_VKviPgJ3rTvOKmkF}0xqOpp(A2M+=K|U=d_-_%%Kx7b4tRSF{WSVfx zugW3idXqFGqbT~RWp&Vn>4=s=0kxr_n~a>FM1A3A3(}bSwSt-M_+)& zdiFiR^2y&SH_NMYV)xgf%q0#QtH$yPs}lpxmJc{)vTxQkX>s*Q5(mXyR?{LPW1%&z z<{0-`x4ep8YH@`fjOx4z$TID(DR7=;PBE5dRf0ZBgKcJN7BAQq`!xqktfFdDSD%`` zs2$;dy|icT2cDvSry7cS*pguLF=J%nR=i)?Txhn??fjhc6@k?AGT7^esi}UO^-F)R zF%S)2UgFYv8TI79Xv5C>MR`p_D!o9h-Gy?Ubg2%@kB<4T%bRk>d6OJZR2j>G5!N$* zMK7O#4~UKK!*QV4D*g*VFT<6EHj96TbIABcDDeMSfW=32=unF*j}0)Z42x~RYMIHE zJqAA&TC6Wk^0a|x_ox$B+ydzc)^m~>yy0F5C}#JOY+u&>7jbgIM2soga%y=fJQNdDwpTNaU&v}IhqiHqu|OSK{l7}Vg>U)|CC!>Z z6<2yz)X->@Uym@1N25R=Wh-2zP8k) zovaORR1vFE)-M02BHz?X84}h6=!-6F^J)mZ3pZN`*;~r8DIIxm5xEfq))@6jJ|j9N ztG8l-C0)-WQxEgdn}jl{{55ag@YMf7q8N~h#)u+R5IlHlu_~}1CdwS{X70Ykl`7mO z(BiY`p0p@PJVML4&3sJ`ZN#xO$3&+}s8^4Q&vg%cjpg)jLPlIz*r}(52Zxw6rY!3P49lnRNLXvEYB+q- z50vxRQ1m~*XZcl#%@UM#-dm7-r#pzzy(0TZ7PCUQcG8Grah_x3+U?5yC2Uxy8^5QI z-5r|kev!NkcZmxtl6T?DucGhjB{axBLILBJ9mft`&(A!4=cW}Ow?O#s=4`?`8+!=iZ77Jo%A)4+-H7E_H;bZUf46i26il0@ zjBXo{QezAJU2s6X15(T^en723YxjAf4nX&^!RlWiAJ%b0Os%=+HmM5eDlp^$y+#D6 zX?I&~RB#l}bw_tVV^gAC`)-W@-kP*u-By2Y`d_?~w73GwusMUpoL5oyyC5;4S6tk| z$rCUcoqCHWF}Co!aen~NPE;g_Wi{HKFu?*E1r@l`6qGA0)8!Ax>CK6tYM>uA;?2x# z78tUDorQZb?evQ0V|<*=|}Y(%VdaEI*>w0o*osSoUGe z;p|aO`wProY%zD(WTF^99rO5S^wpO82^AE?SMaVeuokpm#HlYzk1(e_qH20=6nJxd z^R&QK<6$48_WdN9>bv)Din4LHmXKyVK5?KM6_ePRWNK8jzZ(1~{?7yA(;i&S)IIii z)>K{J;fABD<0|HmGIV3*;}a*69;?lVZcS2b<& z!{kTd2_&!Sy!&EkGDZ2@-q*dL&lx`=4;4M~nx>a77I1qP_BQV{91;0(R@Y^{eA#Us zGgj*I5LBILE}jjEHGTm44vgpR8>q2^Fq#Kl{%ZX46$Rjq&zYO}{&=)HEUayqX53sj zBtd9HT+HaT$k8+qTrFS+iUEEcVxGd9M8hhxJL_&Ob^p5kAW@HNg}vu{-W$!!^|Eds zi^*w6%Ao&Z@bo)#(1-<KK&A8j=T{!MTrx#r-m&jjFe8-WS+rIJVb!9&QdaMtc3@^SvL<5f(uD+I~qT{tB=48 znCD-fY_Ps393asX|2_pTKgP;O>R3kezko7v0Z*Y9_;9e4}<>4^juwuQG zm-Wf}Uh0d%=Mg0wqoV#TK66fS?~bP*$VszhbUwtys2-l5H9E3cC7Gs4+ujne5NKqO z2QM|&)}cyWH+`(%wOAWo2XD%8O|gk+NIwh#sLgt@S~?pTs0<$nM8*sU5p^H9j^<1d z@PvgR%C9~^&;!@GY|#lcbcvaFiUF_m$Gy7%a!!9f>JU{q?}>$}fWoOy=-03R5&oi! zg3s9j_wo=|qbe-n0vza{oFHY&DGdH)b^k|#s+xlc>g-b)DSmp6->s7~^&41qs};MY zL%cVN{Ihdzs_@;W{sKdBYTcaMWeoW}OM<;wC|o@}98f|Q%*B&D>bdz3IvGCpnygyA zv`U-KT}ig|QdhF+43Cy1^$-v@H$0|BS{K&RaB6dAUO456@K?SAneB^!=>b4 zI~dnZE>FIeS6}_=UbL8ng>8t>R#EOp+4~Ol6_no%j$HV6(l8Mc-gunCB|9-?*c4_O zsT|4Y6JUKtwj0)-#SZpo6|BmqNS*p)Ni+z zeXY1SJFP>`wVEKUFwot&Dx-j%&j#XZ!>P$QbW-ls#nK?yy3xj@z?RPKu(z*j5wgq>-H4=HwJPc zptchJ_)_0@LQJX>xUlyn^dz@`rL$|))c)T!S{f)r)B%;Y-q8X7B8#?(8-sw;?x&_5 z7GSYDCK6V$2)N_mdVTWV@*8+`a)4QkIM+X`$Bd%;Gl*eMXOphJ4D2RZZI;TcW2`#0 zXs7DdSw=Ff@?lj3mC9W`1}M!tZY#h{=4S+zju1zH+*zI4=eF3YCty7R1H z|CcnNHoz!Km&+MA^~A8U_eb@IaYg^y#(%dr59+jn)e-3jyP@XN`?{ zF7Erk4jK0P(o}WSVAb#~Na(%0N9I?ftlrAQ*^%*y!5?%`c_rN}o3E|;d^AUh&zh~} zr-rDo8`E-G8B_|GI@9^%_Q$4-{Ui4BmPM%ej2)JlFz>6&E8@SS$; z^QN*3n_*1%KFOK&xzo?(B>}N_G_e)eRD|vwX_$f-L4s`5@=cH3VqX_2;L0;DhUKHC zll?ym@t!$$jnqo}EX$qTuo{^Gyf^rlLF;*<@ncrFqyh-JN2l>^K@U2bZyhDb-~@1j zp|awfL$3+-X=nlpD-O@v=bMV~2MVbjlgxdk_M~R7$sRu*DQyuP6dQ+CVa+d?L?t(G zt<$W{`sVc0qYo+!6{GDdj<2oLjy24Na+>~Y!q+DWq#L9B6`?YVs_up?)XSeH` zUcOfppIuQ?HTi35*73kcTJElj_5xymN9w0(Ny_?sM|2R zR7)dV`zp^@aV5m(4L8p$GgL{#dT%$J?;uUu!-O zieQPrj}8JVXqC`$1El%z>V9eBl6Z;i(T{klakuTxSH}UFc_jiK)h;l;dHs3rwem#7 z#e?!hYe0T$)K+U#m!&>tN!9^e_ z|F1xXM`T3E`yY&kl2%oMA4a!bSCkagM~Ur^M#qcRg47NZIt7zAubx-}2xs2pKf*Gv zsQrkOlPi^Zq(UFJ6@O<*UHkNA{%2y=?GP{Z+&8}hoR_j^SK1vhY)ch$nX|gJfCtiu zAey>qw#|p%o*!h@OZ$1hzGg`wrpM3qms}Tk0MRuA2qw>w{ZnH%UiDi|#Ff9ziz0{9 z(i}!Q{g^}>zUdoto8UV)=D{KMuN<*6hs(k&HE z+qBzlCDW-EI~Nq6QkhE1mm20poY_gH?vK1;^j(`yU?orN^@ z|A1zRF2amQ269ocNfu^Shel^c!x1kj_rj=K-<14V_IXL zSrkBOY?lVMaFy}T`bXux?-$|GE>%HFPR%n=aTG_emWkcL$6%FNk8gSR;^95E$Qm@5 z<%z3-S)Km7TH=c@kAaR*hdd!!I55yt9pJFgG6C`e+dzSfgbJaHv-dpX z^TVa-xXlRGtaIu`uVPQR$@@*wG}0!IOWP;PCHjS_!qaqrTQHb>Hk)W}ZiU9wN6c7N zA3n}{6(~^k8lMzXL@Oo4LGN?c{6plOCXneaXSI;VgyzxmJDgT?5*?6*&e{-Y3c0G-o#SW{%Tr zD@V!x#A{`BFYgdFWm2=XHV(b)q*DG8Y;4NnwHdi|!?sxfgyIMA>KnxqZ+Yj=jw%y| ztbrNri$1AcrJ+?R9K?lBC+8P|+qXmILknV-y1NE9c{I*XxA|Aztr@xN{5xI<%!>y~Qr|fk zVhycKewar!L}x1xu3G?>7R9J-zx(cMLO<^_<=xTvgkDb0Vs70KzSnOJKzY!)&T<`p zfyfK?sTeDNkAAF(w(~Wl3b;;nER*GJs7DEkjC7O%c)EXO@Lg`*%Zg`O&y|Y#;N`N3 zd^~;9HvLygcH&y!|8EDK{HgErQQnF4y2yT=xS9SL|Gb|F?$}!Yie5WTXT`7`tp>~v zI!0QN9HA2FcJf|oB#cqaMDlBffk$Y^c5BEag~0-{s?K=jB?rwTPZXX!X;7DRFYrWJW4r6e9pJIHR<_Eh&HU~Wge|vg^`>`E`DIHl0P|J7i+RwlIBu6eerg>rO z`&XgcZGzlEtVhZ%E7+)|IUm#znt!(@*%DyT+#kFUXs73^By6;4tWl>ap$lTSWNjTkS@Ccp4 z`?n_{8OIiYt~}CeK1s0HbJ)iy%TRUW_gnJ|D{K#9T_VVGJIpD0{;qygL7#UB@nK&0 z{;5khC&0h|Dp_9e7_WyD&O?97*^81}IJ3@#b1PSLX$_}eoh`1d;pN4k(&->>#w|p0 z8Ic4-?ot9bt9o+PjVYNYChEOX2na2}^2H=ltll^k-*Ri$1GxN(@=5Lu`h27=>{o?p zM0gv}?-P}LYXR&ey*(ZEjw^KwAX$T{(_E&Duc>;C2-!badcC9c@>isZjkYKK!tope zWcHRCdK&4y9}-xO}eG8fUR)8*7%UuxcOgjL#&ZcY!jUZJ6Df} z(2@sausJMmFOS(lr~DOE>k!Ds`zjfA&6Ab`pahhOO$4x;F)KShI-*GdaQJ92i#C-2 zZ<>{e&Cs%z2W_9p@jKuHo}~YVb}jiX(58U$6D7kQg%o+Idug`F2e%F!K3f?ya$)f2 zp?)uXR~d?*U#^y5`ru}2Ta)R>&o{;rbE^;*1U2R=u|4q{(9ULWUvB7eAZY=@*<7FZmHUal00f zYf8I^z^##Vn>+e3@iOoMP{2ab!-Xs!R}X(l@PbG z=dz5rlaP$XUjm-`E;~S8-&5?nl;XslLD<_D5q4^m$Kyi6$eIoBM#B&=nCtSYc6Oos-`~0Rj zaf|h^`W+qSq1i0l|uD&tvFP(9OP-`NIrJpf|Q6#(7RIt1Is?J$_* z})qO9-8v@?25 zbP#qjk|%q?`bV+PYl^#1wc&+2_R03Cg=c&%PXA1((>Vreb0jI6?g}5rt8qBRX1n*D z<4x)-rVl*gP=MBx{7K#7hEN&r1_&GrD}d|B`4_%Z=eRNnR6VS{)s`>w`sZSQrE>~z zR2*EG!G8z0m!1FMjLF&I(Vq+~QsXrd2&#G0W^Q(vc7L$HFRW2+*8cfpM51H2Txz{S z`dyNwFn9Lx8Tdj|;X-fw)1SL<82f5q4mfP2y4E6etbSwHXXM~F_)?wjaj_(`x?&o9 ze>E|;zTcq{#}2uhi&LrrfSa#(eW%UX^QaS*$;o--cxN64?%Nt@3F-hMM|5N^l@I1D z6skB#-|K#A88&@y66zHCbFtmQVRWpZ#Q8Z*bGSjnP27$-PYoSAl)g?y+8vtYJScS08 zL^0YXPtR$CLA&^q-rd|kY=lqjB&M33+rIVb*R^7BWf=m}

    1X`K25)Y=1La|KbiS3ZM|EqyY zgPvja%o)$n!5fE!%46Mg+9oXer3{>k_CG>fkuuPicO$Qesk6`EK%etiJjWeDvhJkCKS8nD(+Zk3#XM<>s^#wcl7rg)Q{knAMUSpis?b-x@~@us4GwO z6=36K%*`32?>P?WSc%Dc_;(=J`&zKo)x(PdQB&NP13aqGOP`A8R5b_0QQ-OSGza5I!Xm-`y|N9uV z9hLT84^$Z4Jn$@wThB5W)j9SvXelIqoM{6O6F5OwU`KFh|9iDY_<)@)V>H~B>U_IW zfN=hku)i+*&*AWF@AJ%7`e^$Xo5J-A)wtlT z&ULZ_lB5Nt393{z_9P|NsQ<~0iQkE-X^^gO4ezIEWJ8!wr2FNs{%nJbg;`iuv20fv zMkY&UMi$WL2!p%HT29r>6B5Vi8^v3as15g+@!IYCb9m86gnsL0vz$c;&FPUJFA#B2 zeVCZ><1lO%6CYRKicNb9%t;;M47r0819D3k#e_T0HaYU>q?RTjYxAqFlacrNmn=nR zjCPAJ1`47I9}gPpk>9LdO)r>f=1TuL{sJEWO{LF6+J*$TBhE0R zMXd__ywF$~s_RK=B%(0aTiYxDkCBM2(q)Qqy@9XkNyRWcm8RMp z-^{g~#GnHi=TF+iuP}CTW49uxZOWCS!R6&AOSmN}nrq+I3Vu^I>Rx$tkS=Llxm4W}U<@=8MJxEcfts((|kNm@j)Gm%O zh|yCiUc1r7Za}Trx_?>gQCq$4c?cY)ZO@>sa$dg7=GPdlMe%Uo!H7cJ^BpvJX=#MvuM-KD}^l+!GlYVnq6 zklqEYc}qj3D8RW$-eF5wL$*gC0riPqp zrdnw3t(=Yhl|2(h(YvG`Nz_{kdRKMj@9}ouS?Y3CUe;Q=jf}bI@9%(#e%1JFX7Hex z?@MHdh^V(6fC&Y(Oh<(C$E;;(ao){Hmv|c&%f>5gA-$LW-3)_xX!px5E!euldH zLWQ%oCe&|q`35421@SjH;v&2~ zkgZO<98X^_Ety?Q@N3Jjuc(gR$lYEkIn9fcjp?}4e3Jd**yK3O27jg%h%Fnf$I*O4 z-CSX(o=uVP;Cq0k;MjjyTkFCL{=Z~^gEYq0TJx0_bBU;+x79A{Hf|vIdL$Ip59;BG zqS~WT0vVVktVus`wp~dtT`KPjwOmdW-5+O_QZC}u673B=0uPjgJ?hck7z5|@95-5r zqCi1D{n+iYazPH7puIc>wjDabC;5|6`2wAQKZVZ;ANlV<9Zr&uC;YeAZQ?Z?3$$7msu^K>bB0It-4fdlf~N%3ZO z%-H|S0u1oik_RmXxL4hTB^eBtc}Fn+%ptg)NT+!@f#*J3`+F@ptT#)d(nD8S!(U^r zB4dpD4bjm;{XY+u->J0%8IM~318OsU5gXbJ*m^?yUxuDp?avZUh<6$z9gV;R2B5zH zLgj)fzIFWCYty}d$)uCr!6*B;uGYL!FmQ>-C6jDET~)Ap;i6S_2qW(qkjd~ND>hr= zz*9^AVQ-;J?Dl?eIV0fxkE*Ina}xXPy`1gwTw&G2ciA1l*^*mY3&OFN>HiScmNy95 z^s1sXxsEDwB=7_BbW4yJF1Ky+Q2qTR8|?J`EBdwZ3urfU>?t6STPg|#$xG_i8FWvU zYaJJ&tqak=QBj=;EEfk%mS%N#YAM*&0uN8AZ)_vaWX}$WSI@`SLD8)`v6J6ZrCgV` zrN=mPX1}%#mEY~m`Z7=AF29uBGWXrJbRtf6kHZ%?*12FrtX&~U8f06JcXg`ho1FzW$c7{xB8WhdHd?&~J~hr=1fX zFq>2~x#qWWhX*Ag4;L~Y!PDz+Qo9<>io{No)AzmOIJyz88o-KdfMUz7>^qhyAYGj_va8sw%EK8-L{pM(HlKTOLf^Y1}GaEj>IvXx-KJ5(AIj zs^|HC)%&a2K{o*_{lv(IrWZ`?*o$;oj!DS20Ln8jGO9#^QVzQ>yLp z`s<6_DuOGTCs;yt-!4YBo_3x{m@yyy`9MchG{9lp{cpc74`TMBcmL;~t76~#k`_eR z+&=ceSn?kyj)K{7$uA(db0FoP;ueG3rjYr4ou8&8HglgUI)@`XvQ?qZV@6R5v>`kn zDR85GCx*HboY@sj^gbae9^<#ZnH&fg%(P~3Ui{W&*0h0T?WTtvM(pydW^Yp0j_nTD z+=?yK)S2XO-2T~~ZrJ26u!J8%Oy*?%3n%JXx(ZePUOU;TOt*O)aI#rI2IG|YZ+j&~ zy>|J!<1y{(SHB36gk3=5RcLuc7kgt}AjoHil;_IquZ8GZ{ zJA7mVbfR`Swr&2~_Jge@gz_9Gg}Qb1p?*|eX!|MtPHbm+7#(ea)_WkmHzEcZOA+5o z8j=Bao!tX66nrD4n@&7F2pXyA-2l6N#h5>Bwx9177N3A4sQ#@KT0zUy(u=AIfw(UJ z3lH>6r`nWqbBP`hZz~<#Dj*Q{SGnVul6g&!z~$pOAF@@w4yZGr8Rnr2gquJM7V+_q zSlM4Vry@DF)AP9}**;5crsRr!BUWWRB7Ow;21EjMbma76pXk_FjXnOH8By)msE3R{ z<%05{m?=9F;63Vi=_v$X4kVe}7Pc!K1@!m@U&}8>r^WLBr!Qz{+z6_JGS@I`c^*ys zNaP&${cPo(IinI$sj?j3igUxn&PUjfkdxEx8Odys?CSw1s8Q~}o6|y)b2 z|CRzJwDb%9-SKmOEYY0q3q)Za2LfIG_Q{r$1MPF9>NmV6XtL*>dR|)jJ8rY`J}os@ z463N%o61!IM75BV<@0R;r+`ATi@s38j0#;g;83v5Gs+i|19@vy{Y|p{q&m^^d)eE7 z&`vGIIu`ag=>kfrjH*^2z3DKsf=tdZo(X_N;Vm7guXM9+rV11g z1^!d$8X?)sF9s}es~&;vUJ$?AH@a=40G(RU(k4vbwrC&kxw!ItrCWn$(I7uN9vcZZ ztSD2OBg!H4{N?w45tfDLaMJ*HTf#VfRvrmU<^8si-7tfP?5iM>Exm^pV`#Tg`m#V? znIVf6E%A%^z?0O_X=G%J+_JD7E&%+4*e8pkJbSXC%r3{ zA0s+nW3<5kNLKA(SDk((e76=O%NQ@jTfU7N=?h20YRN{|pV!R1dbL)Om*M21zkz1uIC$MOnIG~;-vnY5U@ss%U>D_FZf01=2U534hNw567D(3$7yH;V3 zV}GIkg!=xgB;>MR>?9X;N9dmf2_Qd?yV4|i*E z6`tdh;|9RQVS-OZtD8q3E`~XhVry5zI=Atp=9kZ6W_Myn&W?!Cig))^wGG*m^S8m- zUT4-v8>jnr=a}WYDBjeD+Cpg9D56uS%A`&G{3Sx(C5-)_Djj$ll~MMzjaU_!(@gYS zVZU7arQ@d5{q7AxMz$4EO>WRd<|@a-{lBB>ue}+wwQ)XMVz3AGs}Jl)Ao&gX#C5q?8w97zv)(@M%f`Y3s z+{Ec??>hDF3*X;jH1f9VKiA23K-foSi{uGszKUCoxLQYVIg{!oir=e0({|G~6SrwA ziJZKUy7T=FhduVM{tYI7Qso$Cr5!i1hr>GtU*!e;C0vj3nO{aYP2Ij(v^wgHAEyi| zyX9nctp~1eTifqDxNSI{3JyGU6S0z8U+=UCSWn}`B89?+$p|3seH|RPy!*?IS8HmD zIJOU-^T8Gu$#j`dfNwIXlkA6+R;iIn?KL%?tJx3dT}Sr3HSoK%LG6n1Tm{yny6R$1 zi@Q^6TH2>avg@Y-4_AI+`u{avSd*^x8sE>W5H$rg-fy1!ZK(~)tgrJapL;;Q)e3xDkzkf7)Q6)g1_*Jpo$fB*UO#+iWGnef0A{~WrP%uq*gV3hyuw&+rwf?Xlmxt^SmD(J zw4hsJPWke@ls?w(1q7HJYl)X>C`?*j-wsfQRzle)@%F9_G^kCG33oeg2DUW<8&0wq z51O<3g-ksHA?tbzh_?j&FHJ~Qlr9;_IZ7ZbKm}obG_dawl%-i)8HtUXr};=zg496v zyRThqhEjj&jHwp9sN@j^rZ>WkMWmxFw%iPy2vZ13+x}7gXSb|GutNSV=DOc%_Q}9Y zH;b0n%?sb$!~&Zk?Yrrq90K;xYAa+E_3ZDNd1Y^d%K8XGQoOV;#ptcgx#RF@-*TF` zCn9KbN5x^vd78nBO1^x>dR0XX4NNi@V{jhQWHa)@CZo^Z{l`jC4=+%is69qCm3fIP z>ysYy=+T!H?CWc&^hG~QN-rvwvG-#xO?%|7Bu^|&tGP_!i5Jh=Gh~?-r0~j;|5yJj zUOS+4p{R#;l^lL+S<>~C%4iiU-y;fD8$E$(H9#Qk>!(jYG}cS{>Jf%6qJ$UNZipC9 zY!shTjM)AbY~pE(LqnV@`7^#INY*7>0e=jW(UPJ_{Qew5%e$UBe2TDY`J3PT#b~Na z4`8lfqf|GqJZfbz;)+5lt#s*u%snXN!xr}=*_9_ZkQ@?AYB!w>Q&%P;{v~$#?ZYNN z`C}O-q3@{Mkt-<4!SmaYQwgUZ^YkJ|E_@LJAE=0BXUz8kU2}dul9+Q9!483S9`Tq7 zH_6`+f%U>NB(wHg(UF7C7pu|0P@dy?;hkmH^Gz>7u6zY(DC*E8vQ)aAMcmE%{HeY1 zc3-`u=YoryDXK#L7kczwYq{DwybXnDiQR?Vjn+lp$+k$%f&o7S^{@@nz%W1L%<`Bd#mna?ul#8!SF zx8KCL9Qu8dY=WORfT95dVzkD$Z>lvd%io5dI)aeHo6ow^1%A%QL}X)L{S+jsGU)lw zbi5^S?6^$|0n1%ROdKw6-#)jR-aJ*FfcxbIiA=sHbLn^zXMHlw9d;jdtM>>md59w^ z7W}RZj-xIo(p9K$@ZZ*YcryLFh6Z(g(|z+J#yk8bOx00uIJo_`fsTpC{qe^BLi@Ot zBMp~z!MN3#zjdf*!`>=Y1Hps` z75>)Tkg%!2XBE+lOJ;Fc@qJ+YRvA58vEoRkxB9w7`rVH~j++)<=sI&Q%d$}zt_`A4 zMwOW|TfNMKK9rE;rrRsbWD0iJ;y0KFSb5bQUyW@e3>u{pDQw07-x*R|wbtl27TB}b z-`x(rgi%VdKEa>Zk{A*cu+xid=aXN!8Cr+alZuSXQ1ChH31!Ub2Z2=mTw{t(?eOgEt;B+_#563^riQ-saHg1Kd1 z#930$mdoi_BB_rFVw%e0rU8O{5|GR-RhFyC6MF8DOZ|gFk9p?JIhTtD6S*D~V z*eevIj7D^Adr;hP?_HW98=?=eQKT7+JvGFyfr|*W9cx}F5DB%3ZyCUzj`vys4%EED zoom@fySo3k-5}Vp|?WYkI@ZX98@xZBF6^51d6O;H`?f7cdwDk)kr+18G z9+Q#NR}Qvs^v)H}rtqw?Wx@2$a|4L8KgPfEf_1O%*dpEetR|A=fsA-T^@3hM?nDoV zPH>T?ir#arOB3}?#e!8g z-=E011HJ@A^Y@v#Q7k_=!&MKAC_F#>T&OX96nv0_BaF`E#;VT?7GsK<2b!76!ZFp5 zx@{lbxo*$+0jf9HB{08$Me8q*=`W9c;n$l;{#+t5&h+7|hozf?nK>GK+C@#$xqtg& z=sd1?8l6SY3oI+M&4^t*eqhwa+#2^MuN;pED~B3hu8O?)rUtUf@2|ktPYxSfIR#(5 z4DdF<=N1`t-`IH}xU(XL+|RLW8tpSgi~(CkTHR!USn=)R(>J86y=z}usl=YnKKu%! zWu3GNPF8V(iJab~^)0fEuBU9Pfx#!ZpNqTS!@Gm`Cg=zVd~DC%%?Pp|&f@FjDMOfJ zhVfF9c@>Rn%sfXhey5u_SbS!u{_?1@$p8ZAJ8&{LH;V)&w4blk@f%M<{D-Hez#-dov^`=#pJELI&eJVOIMQix&z{4*TBz)Y^H! zkd%TqvdVfii|(Y% zO&+OgU4Z_BF`)I81e9Cbm%zudni`qV0C^2u)MLq;3AS~q&3+cY2nK#-RQ_=Hv%FsU zJkpr-xk2o>x#X@`*;4+nWH~ftgp_`&G_+n&aGWqiC&3oJ%eN+rSBeU3YDa9*_}~aq)JW5d4V52Y5^HJWNm@ z`uF}7i|LMs9%dQ{oasTi2RO100iJ-^bSSkm)dlV6|By~(L~8*Tn>vPeab5Y%JDZ2+ zbLcV!cR?4Zfqc|O@@f!UigEk+lbzKxe$tuxGpW01Pxv_k_q(N7nFLDkVOXlo8+;{7rncls5HL&|9Fi@r~W=zY52ShcQAk zz7?y;1A|0$3i&z>K(Lg$4LV>yP0#Yy*IQBD=A7g>5s3}ftHQ`H!4A9hW&)eF;jNjR zwRX^Gnq4a;xv8Y?cckhk$*nd(EZ?!LVMs?NBGOS_s(E|gXDeu>B%G(W z=|lR$r)1oI2c3p0dMg$>O00xr0scP{?mjl6fX-a zngi(SDMRpUkq=cBGg!*9A%W!$t+zJ;pDT86)i6rZ)&D^Bg@bJy` z)p}9ZIMS7?XA`l_wW9*}@92z*Crc5hv+;DwA-5;D!$aC&$i}JjJ?=XMToSN_+qQ3i zn{3UtF-wFy@42#I%L#}9h)6(n0n3rjt6^IAcbqWTkb9()q&P8m8J)pG^D7BxIi3YC zz=8yjNIQiB)OeMXYI}w_Wym;cDeF34{A!=?b~|UR98y=%_R0&3Fhq4wP7{(-8)T9; zHW}&+2^0`K$Jh0>cXjiU#7qIvl%I@I#9XyzO@H#)XW%B;Ak7p{{s~r;g*e8hDuaMl zCkFJH+xU$o4;kidN}Xf?x?0)5Bdj_`1Ta!N5YF}kP8hVALj4> z80E9A0HK*xUgPTYD*`SgXDb00eJhgmg%5=I%*F!Nj6K!vSO5`J{X@^3@~)y%#(ccr z0|$smzX3E>iDuJ3hilnHrn{Lp{|jegZZ|#G&_A&g+=O@xd_G?2pth%HPxkfn>yU|f57 zkMg9Ch5H6KnW}36(I#MfZn=mow~RRv-y&4XT=(aQoGIqJEbl_^6l#>6%9ej#Z;k)Z~W&JnyV=N36YFZ zl4GGYrM#cX+>x$eq)=8{!hk4GIayPLCTFLje3`#VC39`9_e;)N^Z@!k%N#R4k$J4* zmE3WIX6qL+r4>`VKM0!5%#}UeU{!vfMUL{M+sG3OOB}#+lyqCAV487zmgoVKs4bjx zt|w?}U}7>KvmD9i(ZJj5yvruo9(@IbzfDSfH4L5?Jp7^%c;_ZX8VYZBJ}3~XO|mD# zlyfyyeu!YRBAat>SCe+nmo!^f+dO8csq30`uM+F_d`2OG@LW2d1Y@kDNBf_$Gpo|2 z!|Sc}1ur)CkOjnG_)bcecx8gV;j&O%Q>XzJ_xfI zqcXyq69UH7Fbp8p)njkZ<-sA5b9Cj()|4qPrPI5 zjYDiGjV8`1&iO>^dbal3{I@=Ohp&&?&g^}<2n|zQ z(;L00&+S{0 zvBwfKc!5lFS2&XJ@8e>0^F~AB6$82;V*_qtfk$J#z^I)#vnU(h54eei6C1TMEY@QL z^SYs#2&8_Pyz=T8p;coy>yvlE_^>w3#P0fMcui zF+lYzHwihHkD5nU9z3=AaqD@7;;w^gHmcNQ_rNd_^kVpfgL|GqEGmW|%M`1>KiMix z#!v>KxO!=_kxy!V`ena@AoN61|2hj~auh`MXl^f`ASwtis@UiU%NevP|MIdDdzO2` zW^(8&wYD)^uhw&pfwJEolhK)&11dHo>VE9>HBuqEqq~fVx8D;O(<1SoV+vxWS%ciI@(%|A_| zO)rd&m{Jm9K^1tWt5bL+g6d1Wj{^gbrRm^%)dpti4rn_bY`Yxbu_oySabtPx+Q&o%DvgdQTZA&5zw=>%1hW~3YKRCqpB@w?%g(ot)+ zPy*fdv9a}(A?Gq0@sP-1{FCGFNlD@1%<_~c|CxD99Ij-14`|w6tzq*d>cFBYw8_miaA&YBH5XJW<~%{IWa=i8CY!a-vTwV;AVH`u zXPD=Nt}q0}P^?Z~F4?n_oTpd5wEVK8E@GNU%EO7~Asx?hEB{2ME@zycNz=4IWCGH& zwH){7xhfNUXRg~0l(qO2TP;?~Q+YNYye9ZR-0D$(P97{s|H_Oc5;2kkjo&c2I zdoMpXfzRjvS7;DAH>Ndpni7yRLVK4jXd`QRTuTQiV6LZx0oc{CcMar&%?u`90Fxcv zN-UEhLWu+(DA`&``?o2=>0vK@@~z`YNLIDz;dogjg@B45pik@F`SdRIB!8=6^$|RZ z%NpOLfI^&hDqU<&iQk*A?_IG#W>;j=cIo?!HkYi6XNL4uPh;*efyngseXnV=bfg41H8Qq)v6}Uv+tPp1N}U` zpr%lq%%DNz?-&slo@7%? z`yVmra)h$oTJa`Gos$edowU`Oo&HUyF`tb<>!mFb%S~VEqJWtgx&i}D+Pzg;yuSPx z0(WA7I*^M7GRVycAz@2+V|ZSS0<#(0rKYck%n)Y;EAZlCbn|6>@ACwfk~IR43qB$~ zACf6;YUJ57nVu_6_V4#aHR5p&0&}KkJ<^#ki;d#us%;AevV5rld0Yg7I*+E>PHcD1 zyjlWNh|cQABM4tNAyxKW+`Qm9KmmISEbo;Dq&8*eA}{PPoiDI!lPaWD7a>Q^W_Fhi z#(3WHBxMz)NA^CQXiz11;q1r0!i}Tq{G5v zva||f+7h1(yR&ME)>@fQy?e}cnwgx6Xod_X3%c-H?ZWN7lPV*pITVb|@G|bisE%YO zXcb1r85$xb-Eqlf#R#&SF>5xxXSqW|9N)GlIUer#5f49>ANX0EakpaKr%8Y#+;!G> zqbw)Ie0vIJ^QbJu0l)9*6*c#BExJB^FGx3|=;lM>Ym^su(wx@JBJSLM~dX~{{ zedznCYBmx}<{(bPLkpv145l#ui$_#vQQTdkLR!h`E?GtSS&)i==ohZyN#R5iCr8UrjgsxhbKDlhVMj8#%kf%2Y*xuaa7P~?z0 zxtCCEgx(j*UqZobfj!Y5ofyck2A1ZjyC{1oSYJawHy9`Qi!cL4lm@7gMi}FV0#NX) z60JH6SWU-H5r;?)$M5Xxpa2vW7~GIOGI^v42u?<=r$r+-G|>jN&n$~?l|?P!)k0&- zfziBVx?>;{NzVlb9fH>Qy93|^_fj!jwj`7)LMsnI$%6b?=XDnvwIcLE70G%{MsLpP z(`+86|H1t%<(k+AO>{OOYeM=(JcFX!X*LkSVGDb7TJ*SvEy*-iCZqNqAT{c^G@ z)#tL#iE3jHS3{Wn9Jk`F{g=dh@lQ+0K(O$W@@AdrX80U_>!?NleMsWf%WpdyUQi|# z&YKzBO#v-?-6W7O&~r*IRnrHR)^e6`{d;TwN~YJ2zDa`D-;`PT#?satzhn41uV<6b zF-XTpqN%#W_Xqw5q*V&`XRYwx`>PFyB?&Ee?Hk9AJz+zV~_E<}V!v1j$J$M-jn z2}}Jo1G2|uvo3ZbvO6SW8Q?!Y@@)o1LSzw&ig~C0d61C%P23L%1Wb!iq@zX_zldzz zE&G#ZSbR8YtsTR!q9&50%?kV8UApoA({r^__?X@_fo0$*95dqH0E&sn~ z?kz1$KLX9g*dVwox#)H6w*($X3pLT9j{${SRn+~J$)v3nzn>i$%qz`G&U|t(S6)06Bl z=*b3~zQtQ?_LzTCqUo+LxFo0tdXSkR2HPBN1_&qs-vAcy>YEEySd824Y~w=7^M)zH zYZ>CsOO;xbo{DgmuUAEuFU0W(nlAYXl|81A-IdUYL z0$*rK!>p|c?PPt7lin@p<9-MvK?}t7w6tznxouL^)G$Xl_nCI^0=q~Xh`RcTNA-UM zIpqW%l2eaC8fc5+&_5{An&oMFt%ZQ}Ya1k#N|gJ)(x|r4q(EeI`@J9lIYakm=%%8g zvgoM4n+{MuM=aoJ5aHs-U0ze2$GxL|SCr_wV_b=4Mt`)@K%wU;Ax}*Fd^Wb#JoQ?B zN;>AR!OcU)Z=!~IY;}JWEL7>S*sybu>Rpft;3dYY>fKDFST-0SOqAvD)1R0;T;swf zooTFt{NJa8Oc5DwmiD#XZzE!#r(fbdfBN5`5UYmkpitm1D~|MQ>|7ODhMO$`pV37u z2OvrPJSsuWU^rCqVi@J*`7I2f6S_N74eB$ODBY_EbEze#i36m1ltzOGYqtux(B*kj zK~X>}_T7c1N{X_V);ig;xup|Rekt22PXazBIgi2;8FCjc!#^|;GG~T)dbHiif5QM; z@40488v*aM_r-Wd*y4`6F7My^gr%G-CrxCkxmV5>a)SFm4!m>;T~2m+0R#C_gm?Hrh87kCCLS9?vzD2dd~EJV4#(*5pEyXxx(43}F8 ztPBjZLfEV(#xcKf_l={)NW#pS7?|(#bLC;4uvl);27TqLE^GJNBvH8}lMh$`oa@z= zDm>hIIgoN72BZc^;LeOfc*FW^9%mhf~(JuTqdcW zCdz4&+T0}5l0^1Ya6HIW|2OgfJOy?b)mq%u?dkJ}&aqlLQuX57YjyUtMZ|u6%DQuO9lVYxA@0PeTjO}ajq9}y^L6j7BZf7(UMiR)}US?g7R=r^%KVlWg zV*$w8hy?J|y@3=m_uv1xE(Sbd2h@?snZY45?s(V6{PCuh$_#0tfY>fwDp~oAMvGyQWv~`=FdK&`hd{8z9@Wxt%fx`UW&J@FHDY)8bj!grtUh`e)8 z!Pb0EN)uo*vb@Bi2f&MtLhdYs(F9r%owc)ROGE}wgKL#UNNwQRT2R(9dl9d2#Dj?l zew6b>hOLCJZr+8!R~8* zw>lkv5sdlllhTGyBT_ei6N>ap>fVH*Yc%7f*K$B}=LEtWSSx22O_5LU)rJJn(y&@w z!vs_!-XsH}Ggc5Y#Hujxg%LfbIA&N+zZh$o=;Ge+3H!IIR5>AxIZ z=84IPon0xnelFO?j5D;Ct~w$rHktJGy5ehC@0Tch7^EH%ReoBro;0P zk6s6QrH(Iunj^pQA+5|w;{ zyXUzn*}Kmg8CR0=rv|#u)}-AX%EEIASqpmmuW5V$7659XU2A5NgqY2sA&loY zAAV$e6D;eM;3&2NC;JvEJ1=|s8VdC3Ll02OE^;lb5|9oQJu21`x+BT~UfYV1*D0r| zE7-NX4JghmpLc*`g9e*L>Wh(VqzJ%Iov#kiVY|BzSIsSFg@lzx8g$99w8pN^cJgb(45FG=PK%@==?P`%_C>J=zNCXXE5m+BIJiF0UC9_e@ z)KIWqaj2+O->Ux{9RU}F(xEx0gp^IGtG+@K*PEBD`W99rYEOzetIXhfNVwWj^AK&( z)f$!c=bqrb@0-%3+6(eM8=%vpy_7iS3bC25e<2} zdbR{kW-83?tz{yrO4_#MP~H9U7OJjYYUx|<654BiBKZRXW3CdY&h+G6ViX6t%6F z6g8+c_A#B0mhQOz{k8i$Hv8@Aj=Jt{xtdQMONXRQp{2&TYfaAPU{HMP9kh zV)#qa>aUyv{iK(DuAx9jymF}aj{nl(_QrMw^+ceSD4mHzohHoCpAKeM7qO_=a=NPq zqdS$}@cnhl&PIfj_Zb_1M8GCywiU1#_ zMdHFUCS!5o!Fyw|&aljKU^s>acQuY!W?@-AOs*D|!UiOItOG4x>gKHyU$eltg}V3X({fLcop(V zII5||VvC4;0Agjo=XsjA13raN0Hh-p&U_9dF5kMElrpBd#ov1_HqIj{rwXkle=qJ3 zH6G_va-Tbf8HNStLz29R+D77;E_pVfVusN|;a-0Ty;ut0;Jbiqb)HH|h`;^bS*i21 zwYx_2%vPW5zp1b=f*POzz#7USp=`5hcbwys;D{$$DA6R#Hl(BHbWjLf ztvLSbhq9?$8?}p`n3%WC_K5hW%|3ZevFmw^3`9#3NY=MPP3()~?Wm>*1ylq{3|^>3 zbt=IJ0Q_<=9Sz_P`IsOi*|Pzw?PncZ9=)>Pz96o~W5J!EXJ1(oBU7_ih z;tz@n*b(tpq~-ZaAd1n6Pp`LM*Rju2r73$K@_sCXGyYIWzx$8%jPUP29o^l!WME16 zPBg>cKCkS1E^80qXQhZFH*x*gPIG&Dv~a{|&PN3WG7=rWY&Y@V<)Zr%A<=Ki;pMbS zhOaRN0Je_bM%esfOs$ke3&Z>WkEgSKYr+Az{WeNLN(q%TkPbyU1|sqmq(wklx=R|i zfdWb@-6I6)kj{-pi2>3%a?&wi!0JBld!Kv%iSxrb=lOijBX3KqbXculS~Gu9ML*!) z$(TB|KP;_Er2zST-bxyuzj-6CF!H&X8*`7tym_)AtBW|6$15m?jmJcEPj>a&qDU|> zqFyg5lDY3gAzQ&WM44%I)=xJ1)_o}tx^vIb;CW1$-B<4DFx7ZhIwr;Q{noc3GToE= zWe%y0XL5rTdQbzId1c0iI|J4cgKpW4$vQ696w}hWK_ScAnd;9;GJ|!#BZ^6yvx`T* zwQ|qL)6Z_>>!e>+T-=CH9(|72IucxFKPcwx9=YOw*^VRNjY&l8zl=mI{=pUT8v&xH z%)=9ltz$uAeyV@GdXZ<&^iBNVeS6i#R!q)4%S!_0bAK$`=Y)%$$l=v0v*yTY*V#xo z35Dv_t-dzp9#k{A8@T0a$y(Cf7zGVMMGtTyP>|iCwJa-39>^&;CX90sMckw7t#|@OgXtNw)8PRLyn{n6!iHO-RQf_6}@{TySC6^;RR;HKy&N zy0JS~_>In%qEJOH5Aaj&pv{flxn0j1U=9ni97wo}`b!`r6c9c#|Ck0+zt7AvWD2~^ zWa6Szff3^Ssiue)*R%%O5W8xR`Xr$1-VtnOFQVUe0$w61rJG7xSgcj+V#}+lss#Qe9R};T(p$e6Xh=yicic~4Yz+C-(j4Af@gn)|%;9KpO|+2cWAyojc75;J zicbB?EBcr!@ngo?HVAQHygU?mqxnC+Hyy2qeeXJ~f((n{XENi=5}~NDa%QeQh3prm z=C6k8@4Loqwg(#s{4<(2&Y2cx4^<>B;!gC(ZBCjI>`uCBM3_zmk^Zc!-cqYCGK=mJuai}zKv zt)GJDSEgF8Y0$aKooaf46=!2(yPVV-~>)ix&BRrNjL&rZAyCPw`?Y6ZMoc-54CkxpzJ1QL#WEf|g znM0ij_QcP+8o4OwafJA?(N>zZ4{Qr=bDYvxd&IuZu=-fNFJ5NA6?(mXJCXee+t%_9 zE>H2a{@uX-9xTD0H=|!f|6o_s#Q3!2ew#->=U)1qg3>RIWqb)V6@P%=<`-=;SF(>J(U^)5i?hc+)$PfZ!r@VWL zH^0L4-aT~90JX?|9k6%swhw%`aJA>0G`eAHoS68RaM`D^!ZD_Re`A{Oeye#k$hZYZ zDy9wz?_pQmB6v-H9gOCSWs3r@gy{zMgS#Hw`KbYhu8?YK7{vou`qyZ{T|%M%Hb4=i zgP|Hy;v|V;-G40Wo>9wSE67fMU zxz#b3nPfp^a1(YnuIo%s5bSDR4s@5r5)hn*5I}q)7~)K%Qu(-AdrEm2go+%>dv zJ_x3JhL9TYKD*?iyLy^NAf95B?tG*jO-J2HYQyhng7EU9p%87F%zTk>W|IJG_H@0DM&(PQV+JJ%TNuQ#}LgV zF#AwIE&gV$TCub`nu6nRJSbQ@KHeap>BhCYj2A^^zcfp#bvf0|IMvSC%B(^MQ(DD| zMm{O4`6s5ThK$L$Cj!W)L0l?z#((tDnZ4{QpZ?JCRl9`HemGzbtTqfYoyy5kWSXyX zTdq!9r5C#Q&+qu=mwc$4u_1)^0??crV^Gti-!xM#yMMS+g2<*Rn}&Vognr0H_htrL zHEu+OML*ltLtihpB*Ie!~xMGSy%?aNBky_?5X zJ2_@;hBmO#BFFpCq5FFuC+QVDx^Pdo!*7R#VEdMrZ zt4Lo3toz!uAPec+B+5_~#x*m$d875k{@2!N&^z#{Vr`8T6Z>($cXqbfEolQfR^I@5j+@)ED!zOV_;ss6eBr%kk6K^peCLOW8S)q)-X3*dXGQ|L zYP)>}MM1pAusIzF^N_c@(F38s$nGYZWU&IJ)eRE4RnG?yM`h` zqwCr4Q7*y=vuOHjZY5C?kW6&Ib?mP#VO@i-U;0%M)lu4 z-%|fFj=123{71D$#8+hf_QeMRn+gl*domQ2_uB;q?`f38OzWnU#5wLRx~Nf{D%O@$ z1NhY?!kpd5!Jo+fZ_Z;^(wknpEI*gMz3IjZpftf+dJ5-HP-j>aEH+h}c&+ui{~jR8=rdS#Q?sI4B$N0OeRJ%$|`w zis)IIY&^b}Fg{xPV7d-3YHss^Gwk}at~n8iV! zn_L+_Z%El9ldkp)-esyVJgc`|kBuv^icb&o-VsaRFKPBY4O5F0NjY zY)=U_m+c68^6_bUB%V7^BJ@OfmFdighap)Uep$;_;>7%iy^C;uJncyeuu*Q=#WMpC z`Yza~2|ou<@xTql<#bJ$CFe${*N+wG4-5vB@}nmDQc-qhuy-OQ5l;L8s2%w0y2@mm zYX#=HgB|`xi}t=x)-Y6Nl(O192uZ1lF5;+L{m9->E+7=%$tK}vL3RA>99DO#{@YYd z8(lVS^SjBgH*Qz1Bx9e861@J&X%mkQIz`Gj?73-t*4 zv;xnRF2|o$JY5iLtT7ET_-UB$nO^BIE!3<~Rn=%K@;3w+{rgozc}#Hr*dVM^Kwf|Q z7Y~d@kLt?{2=KnXHz*tMMF1GY^^JxF$V~wPXsMv>9?|!C-&i|Nq@`DFjm>bphge>tRLGPra1Qdr;@ z6ad(-?E|D_t?NDRd4U#7{J8we{9&!!!wq4`VSZn7&X_Aj5%1vr_x|HefdIM_m)-x` zQv+GaCeQPiRF!l{fOB?FuvCNg>5&{@hE}ypG{Rq?{x_G)0myeLV#XEnA+}vjO78n} zivHRgtF_*p(^^|8Koz8g^)uUSv*(*_^s%sQn`d%yh(`a4wj_4XHBUgs!Fsz7H*IN|y$sKq#+he|>! zybS+F3ElaNxT3+MfnNe_{$$j``*DKF_~Iz5Qv7WtC56gFJ;P^d=C2PV?wDvQ)&^|5 z0)liA`J5$|5{-d%pZ%u=X|I(j4g@}bC3QMs z_QGLLI}GC_n2Rn~pT5|N6^JRfxiGG5-h1$dX<4*PPJ^bY`j!9XfnOw7nnng^RU6l{ z5bX~X82^NR@v7fCZR1t)JS_8lqptV%Iv&1}<_K-fChg5&j0SV~>ZE;^u zO{~K$T*c`Iy(ZCi9Y0}msIg7V#(Cz6XVRtEo?)GOZUfPkyb_RrdmVr$^=JX;a`o`( zB@6o={rhh?laWNm4*bEIvu>ErWsfnX$&Ut(DzZK$0=K&2k~S`$e*5zKT`QzE;8-0L zk=RFyW}#(&*Q5CCirg9jx}1EPSkp~w?YX*F1iF-w(IfAtcy-sqjZI?Sk6qOfwJa|Q zUejdDJ7WsC{o@?1q{&&FZiwUSx)H21bZZj~xV$9@W4!$#k!jUn&RhqN5DkoXKW<+k ze?N}S_KX!S#$LHLoG7f+NJ0ti`C>7vvp1flN_MUCw`2b5$d%OwMi5%$ivZkOkObTn zcydr2fJTL#A+ zmTg>S__d7)9HF6xx7bO6LU<~!WL(IZ^v@+2nKJ+sjWDV+Axi8M%`(%nwkiR+Wrl?{ zuK!u(2ky7Mf*mXYEsQU;o7&P;K)l>Cr}|sKz&dZL7sqH!mXvGH^KeU#1`21G0^lW# z`A>~f#IKZGlltJs6r||dnvrntQmZfh?(^68mO8_tyD*jClRPqkO7-8Qj5ub>TxwMA zuuUM%DMCwwsF=#_<>>wcTv*?8cTxHz%pl~nn717Aki{$C7Wtrj7;vwe^FXrJ=~x$U z3s&*W=Y3aSoshj5W5@dmLgQAT(>NQ>!UfX#dG3Pw<;MzG`lMdVQdkPb-C$zapE?TW z=5=B+c{ibgriei)rxbu#2@SiwV*VHKOU0rWVV@7-Er}n0eVXwsr!cR)DRM~%c*me! z&0Jaa;RL2;jr5EZDR8|7prf>7b|m`(p- zB!?k*Kjh9UP(a@Fm$@IcV5QxKQwx#vkEvieFO){`J9O8dp)ea3bYHByGmZ6p%3tbF zDKgBL@99lbN6)R(Hr6CWzVxekR0Z@A`InD!! z6MZf{zPq7JTwG)z{DCmLdQi0M_%Y)0!Z$7d2 z`_823ZtDSyZUhMbE0mY>)sh|qgQ|mhf`*i{%}OFoB^~F@>&#<~OLVGk#%Il%%)O{C zrsB+VRoQJQ?Zue`DyX$O#j4{2evV%x2PI+~`^DaEEJ`&QMt#ps=cJzM(bHGVkAM1yD1_d+qvrCr8D%Q6c(_0ysY8hA zR^;tja?uJDIsyR?4MLSkiN}}XLa=&covWk&@l2Rdj-_r%vLRJeDyrUZQ}7)ttddH) z%cq_-i(=eq1YyJT{{*0nf6603fpP9i{{brxlBu5i4=6;H6-q85V1jX!ehB59#O#I2HvVuO1~L z_1S^Tn`?P(Wum~~^1T?oGdn>!ej_cx*Gkr^*7Xr-xiw{SR8V~iW0{-PH!gD<&m$z9 z5wn`bO`e?q4(YK)d)$(+z~GTU0Omir7MosbL7d*T(VS?QTR~91*rFibYAS+0p1y?I z@?zX4+-Cazw5tlO+kcpfTm5Z*dp#74iq^DhmJ}cW999prw_el{yurWImz2eRH||BP z<_wY|1W$k0d&46MkUX8n68AL3u{*o0T+2=NKm$D?)Mk%Lt-*xB*qW)z#*T%`WbI7yz&6N9opnBp=R$hP7kBO=>$*`c(+rS8AN8=g3ev%{7**|c zJI{FHfecZEX{n~GsSQbFd2YW|G&lRG*Z>auM;J4Gzf>zZQ`!H} z;=GAUD|{CA-#QJ9uUgUVd!(gjwzQJl-xthoU-Yqu`}(8kw)Y$w95U6(N*x`O=YT?= zu_;@sh4w#2#G(w{?~#Or!vpG!vS#g97o}onV(}r?^}XiCb*D8Bnil^Sem$M}Yqa{c z-1YfF*Ku^#Eu{<`obao%VBYy2LMM^|IzNjl(IT|Cg)^oZx+k~+~&QepCvM+>i+Xgo%ui+Nv` zrQzzivv(6f#yBGMzGxT#C}848S)aJP7>e;mzIV86>Uzu zPhPtwdo}ZjA%=gW*0y`GW6Ht=RrL9PBk4J-j--u8U0!`GtJn8!!*=bhXn2cWZ04haYa_d0s7A0q}!Z_mZv`Z<^KrHi>;@v%h+2JLRt8#h> zDX}l~=~C!Lt1e`ui?8DXt`Fe3zEr%8RfiBxH^2>`7Qz9R^asJHn6xpde>1+^7ius2^JvE=#JE}Tsy6r{di9(p z)S8Nj{zXIo<0RD8wW9kMo~H$z6WDW;S!};K7|{_GoGjn1!i5~Stmu7jGc)nGL|an* zSZz4nY}5o`VPBkr07-GeJ^z~Yd>{|wVI9aHkZFdh@3#X1Te--GLi%p+g{jH`iYip- z9u`v+$VdMasHz7q6#Btcvhep_{^=&DGC;Qm_zIQ+>?wWoD4`)etF%Ob_3hdcaGj9g z=XVsxWkdEZ&lW27guCTy-@FB&rnIFHH4;c0pHn%yqqxK`(W2{Oy-PkUy6}AaLuU@G zgJXP%cm{iXL-Dno8ofEhfV~C8=k;C%#`-agvRi~3`N~}LG=_rJW?+)4ph#Wlbw6{y zXJdFVH~)Cwt>OT7q@Jd(^+ZF{4z*L+^gN&J+>CrxzDmbIQ+8*XWKhY$S0yy9>{lrn zJ^FJm5OVWL{s;i_wnG*zn)L3I<~uXfSf)~N#ccAHN23o_%&Pdgn2SDz{$|vQt3<-a zu9fa`lNb8TvaHRXhW=Pa*l8DBfe7KeJYpqmVMvgzg6kkKQG3+!EwavEQf29ZmqBpi zD&{u~eUx+WpediCh0ePE>hX({=OtgnHLvYj$69O(UPTV5L{{dM?a-as$7!cE%5V7m zOzATbDx%g%{rV@P?hTJu<@+*Ndz-W?Q00^RU<7O#G|KtcRhjV+eEsd@%bykv^xWAG z6&17U@bZut^pQv_V}rT|aF>Pdk1)S}n(wUzPx8mgf(Nx`V2UO)d+btC8=5~iP}8K| z-)OGE+cslbZV~C;Bqn-bXSJ!|-dy+DM_SC_zo4}JT>V$=qVkQ9GH3;rpbJ0tCN^J9 z2Of}In4xG#(!yqo8c3u{{|Qj3Qd^|7yYt0=&&jwugt+$ueLiPxsS)qH9@MkXD?$WTHBR>$3Bd>7J1mE>!l)WW#K2K7KMyn-OnL(} zFV(t(c(M)U|8$4(KkmdqPsM7)_TXC7>MG~TRUTvigg!+1G3)Uj>8gslb8 zoG@A=hhY)>bgY^(Z$B3=*8HuLgHwJtvpX3Wz3-yxy)@e~@c_iQfcur+C6MF4`#KVL zyrOVOFbw>=xFWTG2{`?MUDuvU>(M-1ORebj^k~sPmqC2gQ`CCk7_26@!C0E*0{DsJ zr#ile0WXj73ku(P$>l*twf>u5bN37mEAWuOoQ(Xm($ljmA@aC{Xt5%zay=u@SxG~`KK1Hod>s8tv(Fc$tR{E1 zZsS{e7Al6=?_W#8fPXR_HJ8Qf#=5@=Yl8F+yx^KGSU6;&I(YKrqw*AerZU~Te2I$#i=Fke^Aa#y~OfzNIHNh3|7xr|rG5g04Cu>R1& z(3g4mJyn^;CX;GA6uAB9%yN5(RoFQ42twvx<2NSn=U*j~T#ZMMjR(Rk3L^R0iPQD8 zK|P$QY-P8k!1ZdU-UTksN3baQGD`g& z??(5&Qj9J zvH>XkYD~+s7T8^lM8d+O?%aBNlGSZP%zf+MFfZZ&l#x$_?9P=F=X7mVwK%TA3a2?{ zy!9~$=>}(yP3Zz?d1=oIY5O0x)bN+Xw7E2utchAob14M|NM}R0@MKYMV9wpKU>0n2 zjr)YAqF^|`6A;*HXd~p~)>mwj60^j{Bw%dvQg4WBOaEY{&5MvA+0#^gP@?!lxAbOg zm`u=SqaFW{d~=!JD(kSVVh4xXJbxv4B!$!g23#(N?9EEAR*G7cA7UG%L4x zwwyX{g8WW{MXD9er0E&0?U6nlf)fyD{K8#u?cwIuZ|k&czppObS|{1NKr?!$dDSAyS10jY9}(9fR`Bb4{W45*Z&!1^n5A(n zJ-0kq&E%OTjd3RW-#R)ohPw`POXKe1Ds5RX$D;CO0#4ASEoX#enB5FB3N zm&JIOCr+k@Dz3+b?n&*J^aIHaW)A1;dfiy@C+Z=G2L_&p%Ris~2xE8uI(@g@bx+86 z0W{tx#;t|1gjFo4aM@fp)cYp554RN4cV>ZaJe@g)LAURm(&)Jg*`}20NE~#_Ju$h- znJe_4MHyTvVsKP@)WITmY`*#2-GFE__H|>S!xo!}5_}EJY5b()V(ntne*JDdBS=x6 z-Hx?U#HCImBSv}*JNKN!T6>T;J?7$MQ-rZ*cn>zS@S)rs?l>CH8#T9*-DuY&cO%we z;5$6A%yS3Za!E}EEw{;GY5gsoMVydMIe%S{Glno(oDFZN_*Q0^6Wm+1Gn%BdT}b|T znU^o=>kal>11_^p7ZeotqShvIz=Pg|l8#XnPM^>*f>+?Nx*`}{5MOVXhC+h(M|AH| zc|E+kLfQEykwqXu+Mh@#XLp<;;w5)~gO`$0T5UOa0Gn3kAz_#3L1pJ;krTD>rr`4h zulPLjPh-SV zcRYSnf%Yh%xU3g760gP`rQ+&;C}FeKNXeN>vo35PPOx4CrnT+ zsD+^TBlmAfqdH%(ce^L_oSfWmhF87HL_2hP9H(wuNkf~3qG74V#C>+EQmW9P7bgz!3wxluGuR+tQ>s`9zSAHs zR6^`9B&~)n9;{8WTiy1U3H-hNV9_FUt^P$#R~%z{G*2K-q4J4rEFT1N;1@~I`IZ{{ zcpy<&JN7^fgWWVMU+l0A39w-va0+@lx#ye*oa#F37niWcLszifJ%M~<>{gd=C<=x;z(I%5=zYBvL_v({4dnW*gvP_LLZtf zzd0ZD4a?)g{ohH?&Gis)N4bRMufa|oU&mdI>+m4>Y)}hT;0czudwXp_%^AEJ_*ZnT zSIF<1GGpF(I{REt{G|85iSk)jKveX*%3H?H5M8~r1KA@iJTQT`mzslSYcp&I)B7I= z{B|j^uSExLwm0MX_IEU#{WRQLo73yFwX)q)I!3myoMV@qTIQ!4DdZp-bMw}fs|EJ| z`+$``!kj=utyX!ai98REfy9RQjpbBs=YGP)IfhEsB4HJjCrP(kO#T}2w!G#w(W@zj z2Ftpx8&YoD^$ST^YJ`NKv*_)AOn;uzzVawL$}(H{P-RJDXF~Wz-x%`qH@E+2)^xlpIvn{w*2o}+9Dt%-c*H8FQ!X9-qEW^C59sThmI}64qO`n zrItJcr}Po|{i2BnC*hG+H?y?O_Z$V!gX0?pG?THgDBXA3rE6 z^pXKe5>l|z2HmZ)>o3srm}E>g(z;J2C%v9r#;;_=HvUfcee8|ea2>iEyX7yI52GZY zi(d=sRO!_GM0F3ptDQ;3QtClJU`PD!d@Cs^(2v~>z9nJ<&N<#xkn97v?InX2&SHvzV+jE7GIUXdnDY`@Y!cohMJ zrp?`cUiyVuLbVX4I**f3qNSDSE#R7@WYXbil~soPG8JQroy6wKhE6TaXSsC zbmW`oyMpV2V~NUnP!_5t$hPB!Qa}e}A#iu`J_C4D&-9t6kEcc!sccR|*A{~+qFdCWL-~m&8QsyPk4Es}eWk%WX1n-87HV4T`(}Vg1NT51`?0H@ zas}2^CP9)_)V3-d<-9sV)ex_|Dj);AzWGlPN_uesjfuC9?#rrau(IU87?FZmk$~Y> z(OeDFw{egBZ*!~aWJYRy`xW@}dcq1&odUy(sKy{&(b z!!=eTRq|?ocfpOMs$O|KDF0^yl;uZJt(Wd2qoC95L3 z<~OrB`wKUkp1ETDQ@MuoNLm8mx^1++cdoR$nM&SN$p$W2zrJny(fzRTY7R4VxpLR= zGzMc{1}DEVD82uR^-X+GWot$8^O}hl@Yit@!L2fO=Zk}`oW;b$Zmdx^@iz;O1s7A} zYp@cBKYw+i)?JC3={y)ty+UtMP^xqRwnS1PIf zR}Av!L=VB%rWSK61Q`Ad^R8 zn(vBDddfhF(xN`Hl_D==YWLrjJ$%#<<1HeiJVc&02pLO?>3U1TUd@q83F4e!=G&|< zTGqYs6BVR+kHSOKJ=Fi>0u)Y>yDFowO`An1-G&;bp7=EON1Zz00=HtW;_EW6j@1Y0 zpVm(_L(_8uUzpz2&QbP1XEpecpb=HKeCzxEe+q8F@Vy_~=HtzeIi~`C0GqUbsq}ZT z-{2^qjcqs4`$KX0oBmp-RmUx*|EN$sR=fD-N9QC8Du7MwQ~+Qzukzx_M(e9xI~9i6 zdnl#mXKqsvZenkd+@cdFN)_16Vx2#)=6K8-LBW0lM8!o(5jC=&dB5Kz{5~b{ zl@m&=auvp<4?TyGx#RnAm3d* z$#(n{)*>fj-twQ{2k$#B&!z>#ULGo4qCMZ#X_LOwo$(WCm(-NT94$tdUCVWSSjLA| zOFWDauheCUR6j<_L>n1TZyDK}b29BE7G4|zIm=Pu(CS@Em+w5~uR}{+*2P!=Z0Kf4 zQy1G%8rKMAQ0u@gU#gH>c4maPjCSWjMZFCXynZlc`NAZAa!hYDt>I zzP~5sqBKmqeOkv8nlFNhB4uL3pE!tGV0l)D3|3 z#bAW{X)mv^Z^ZR%qFPXtBmik9H=WOEqa$JOU2+^RWJs}DqLXe5EA!@x2+n=Ku`&PR zc7T%rtLzGsp+GV(X{d0*6Rj2Bt7!bk zncD45==b-Ht3=Pgno!*i;Nob^->Eq15L?=-xib(n@jAw;jX`H4fWQtd_Rbhs%NSgH zFjz`0!OnE@xJTXXTA}~ZmfGcPuf?} zfxWC=V@{dYpzAsD+|^vrHCZkN-v%9A$7AEno-5$(SGvTy!5fe-Xoq ztPAUdXJ1ll#VnW!t#}66zN5HH<<*T3Xz0W(o92&HOIXUyDZYTF#DWh{f(61$JjB-o zFW_y_bWk2KPlu&2>G>zUl?{gt4m8dT}?<*4}4ImWmvFn-x!Vo8Z5gx|t4`_^#IX{ZsVO$_9mfh8b7O+8C;^B_)Ffm5x zpU^zQKpHNsW>pM%K#SKL7?j|{-@UE~#H&2Lb{={d|7?S+fBT+e8GNt>eEO@gs@RTf zV;Z_BQ~V?4z`JV@wz{>y_)l^z3&8a zFc6`x@Tl*RP$gY~Yb94g#8SS3)bgMN_%B(FlV5Y6Oz^c#GG211!Hh{x0mSMMJ{Y?7 z`u!gp*x0x~oZ`pHgzG|UAHq4S^fPtGMZxJE zVJnXuGcF@yC39cJ?Vpv-OjArF6^2T)S-%Z@XfHuw^yr%anFi^9jk^*7%Z0Vp_-?sK zZe)oiTT7{o{(2oTAt9dHtK~H~;Bcw-L%%QeFlX9Dc5q-L+pqg7cOJhm`g%LCN`<#k ziu^Az&vS9{;W%9j@*0=vn3ipjNIZeK+_Tko{bD>D39#qQS}dj(opE_eRVcVXX;RCX z0Q+`Pc&ye+C$aNgJ~O^HjMt`dJ)%+Q52~r@;tebRKfxA&$&0cZXIp{vFaOoq^vc)Q zP^kdl7OD%57ne(a&P$ewaz8iV@OSVZzn&M4bgD@yn4>IvH_WitlblD=hf=R?+!bm5C7_d@8wyXR9?Sm zR04MFs!@DU;Xk)cwzg{Cg|tmBy2FbatAw9(y$W`pB8`;K7=3-WXj)5G{1`Aky_30I z$;)}rdzh_gv#8Qt`eX~6{IhgrZ-UEa@ol&Mo@<#FRXF~NOTmePWC9gthmqdh$!ME) zQ2>wjzaw^t*2u0->}6ZXL8sl1=<1E|Y08B&{R)yw<=gz&CZRvn|xws450_PAYb*EhTKq|+yq2OORJSbP4vIBnow_$i8cRu#- zJD*9USI>_dr%(WYdVU zawjuk%-oGOuyJ|sheD-)?H+z(4K`=H8HSM_t4s5Q@KirbIC#vqN#Wv}f?jCf&iwse z_F)F&H(gwMz$N~;I)~@t=U&-Y37(&U#t^9Nxv@Qt?r-R~uEfKUt0|FuxmEn1MZzP9 z^GQY2S#S)Bl+LrXuU;IIpxVr(0O5TgoGgBYZ{8f3bq7gKy-_-kW5>fdY(j~#`_Egw zuU?eF=ms6%e$2(58mAEzC4lFyYZvn}!og%hYE512xB(t)R6eQ;CF~v_91&Hdl)-QP z@dB4R$c6+a%ZQ;mgdq>{i(3)4dWn&dz<1)kQHG*jPtM#+hd5m7-F?BxbAFG z7vdkiyHh@PCV+wSKrtK+jd4{0p(z|Z4P35h_B<@RJr?fXcVUR&ptD+ldZfwJmEit6 zNsMI_;Rj>ktSFv-%?nLz(c94Q51e~+V`-m|H?Xs1{LUTZ#c5EY{JVOlixb1wkO^aP zS!`SqQKM?L=cMz|EW3AJ;HT}cmq9+%T9!HY{2wcCs=NiTLzTzqnR^l%!nVP#(W1AH z2_>EUbfp9D5s$*UrU;?4iCtW@se`H9JXi|G*nqF3kYSFpX>BfS0hT6aqkUR8J?vP` zwvE&~zrM3IEPNkc6u(;6Wm!%(Nr`BqYmWPVDwDSugU1c7;-gaSE@#~s1k=eU*w!Tn z$DQkz^(*&E3|te7NZPAU)=~7x00kO*KsC0T8_3TguX4b@@Fx-m%l$GYu}V)g$DC-~ zHLX=U-V@bsx=HA2TEES4pb<^Qe9z^NR3D{@GO94n9+mtfx1YQ0(4eWQF#R9v2oSxV z1>_B6xDnT1&%0NTQetOFt`d3Ig`^jGYg}n!Q>@+jFJbY0DFm~$lWjhE6+}?gpkV1_evCv^tm~ zSf@2Xjs`@G>X*ur=s(7jzNI9ndYyYd()4+|84S6|>bD^^QEXoS-SJ0) z95%q+{Z--Xy0k9 zeB~Z}kIa1u5ON}M>RgJisqiy>%k&9f1XB3?0W2}wa#MJ`MirJs1z-qY-VQmn+lob6 zCocTH2zLWm8(V;G7E{hDJ1fv?nK{+E+0Lz0cBM_W%X~t1Mj*rFZp6`=5G$dd?opN` z?s!g>Dc-v6qx4M>5l~M46AG?*4t-08y9H9r~2lr$D1YJ=KKD@;e8 zTEhY>u15#sQjXd*B#dl1rNs2Un@F$EfY59qRthJCno> z&1&7h=eB7cY3HfS(EqMd2aL0ZuRy2(7$%Y_g9 zXa)!M?9&o?Jl@$B+y9v_RS~QYW6?!sa`uf3V6yEIZhFszUTB4`q?G6bb2=e=qcWvw z=`3;jg6|y2y)2DqhJ{WdsAJ;7Ej1s zkC7gq!%ZCY%AU0)>!q`Iy=H6HM%I$;kphm)_5I2v=2f6*)PuM>v%nQaYkgf}` z@;$aOIEQlBD5kf{K-V}pw0Qe(4@uasOV%$_d{W}Bi{{oJj3*k``U~B4g0Lqm^;}jr z5Vy9Y4dCL_P=Wqo_-xdL)k(`s{jm9v)dF?7)X~J$F=%QWe3=>kk!TsZjE0IU?8r_7 zNDZ@qnZoEPaH^G6ynSd1K{yv`n`sq2LN}!<Z=B3qIO37o!GHs82H%fF2hrHDgrnJ_Y#)?Jn5wNaE zI`%9-?3A-%@97pwlNftm56j`T$TkPJXb(Tkr@~^gwQI}%+#*mKE_^u0&u!=qJqe5q z=Wz=Ma!@<-y^iOdcr^zETLPsmozPr*4f8;_YK*a zF7Ct9RNZwVr|K3Fufe15Trl|N!I$OAPpV}?zeNq5Y!R_Ov#baK;qcdI8*JysT3YR< zG8BbFkx{`c+oj;;nMK!1gF6caKA*qCY^M^JgktfVzSIooo<4?Z{}e;D=VnA=eSlCG z5JiN3h%JqK)9Q7Y3Ubv2glpw$n1+-*k!Xye2ZSuIfAxaY1tTJmvFu#=_uDz%JY^iB zdI&PUS_am#AY<6WV4BJOAI~tsqU-sIw|aKL))L+hBTuFID|EzdJr5S7E)M6T5bTk44aLS2x@763aPt=>Ad0Yx# zj#^@$lrZl1Yc37rM*5!Q9O{Hi96Yu4Rsj_s6CZQ9P z@9FGE|jUYdta2=}Pca59y=J~6*k8GXN$V6ytOd}`nsxi9;AW@Z1W0bb9C zxJM&S2Tt#lrZrms);tSp&ylq_Pfx3LPeH*pFn=8Px~Lbrs5Y)5MgV{v)Sw@T6{o+XXxjWmopDF`hNx*{je5Y6NNpNXvJ$~Ts7Qmd(q4=tvk z?t%w@Z&*>4WEy7&Hvdg9<w!yD;oPlnO6Hb)1>iOS_$ztArrNT3^BQP6)Lg zVH$xd(#xxa8C;JAt}UV?kX*E7RW|Fqx~@*QPi?bCfz$~*=?StQYN@s+#m7d@9o5Rl zonGaHs7GRsd@!h7uGJmvZs}8VXkKUp3vxD?9vuR?s)!lDnKW4)5>l=arEvcVLM>tw zvHTLSe!_!09vx$ss;!W%(Eli1npeIb3Pdu57yn}+GzKG)imKKuA^ePl*G~U(KOo0= zK{ESQ(*Iyct>$jlsd|8+$FVIPy}-aOD~9(1rHel72*MiWt%cV*t$m=-tTJFWTx>S| zKSaBQQxuH%zP-WHDX?@X57Hq>wGf}BM~=$Y0v<)A=K=4Qm z`N;%A^k$mL_bXK@fc_?))aui5`+O*7wGWEY0sm$f-NidKBl?W5K|8Fs*j~^NmMcp{ zL2syHYA*EjO~Cup)rwEeBzH|Fq5Y;~_#HJA66y=qSc*w!n%tb_*8+<^3;DoiGDn+; znRm3LOK-cKYXPls@c|9{_TPK1@Ok=B*p>F79wDFba2$7}=9$2J;v;|U+eswf zOfwB)34j3g=m1^WTPAhQer>9x)jj-`vX5y31+b3uR;0spFdyl z1;;WR#A)62uBMgxG`p@;bbK#tvg~bQ@sSL%&ZQq7;T9!4+&44I8ZKoAUsPsrlugg+ zy_+IkW}CcMP5^}LnN9zh?*Pv-^nOYd|5uf|J)30_gjeEayp_vsJ$<;fq5>y@)I;aY zRo>=36))eakoVAE?LVrq05_Lho4^X((nGwP(jW6$FFf_KlV7trnUb%xSlFQt7}bPX zO<0Xd6wQw%H}HX8u%EzdMn*oMLw={ zW}eAHzl6TZ>h%!+$CsiI^4w)sw*JPlbKfLLtDG57qzQM63D)~8$~LD(?@pYFdqYy8_=Lb@)yOl9KR)rf!se52+XK&59=Lr%#UP%tL^s4# zf+{zh7#+&Z|I3=mY}Hg9!Ab5fC~9?BH*RiNp_$zs3LcT=6G-2YczlHdTd#(*fw7~L zOxq&`?+sB$b>_Tx?j73$9{TCD?qMaMe@1wzi(x$eMzXlrHH)R*tKcOL8<;*F68RO)^_#xMb-Az>#8te#6u+81HbIawEbFVnw5=O%lfU* zZ)zjJ&W2fAXTb#gdgZqFam?J`JNR5UISJm_L>KD!vxy0|c2n3zZlnmryDMaeWZ&Xq zxLahf&UVYW{#yBs*^My3+=)Z}^F0fQR(+G}_I%q(D_aksx^>0(A*SQ+x?Wk>aQy$0 z={>jm1LdHhQm9Iyt@%rxp*+ts=oTvrr!pE9=M z?3^9xWFf%+@fo50J2{CH;?xesjoy+z*`@*}HZ5brW}STY@^;-xs8QSjR>& z-xq~QF=5PQhnuUX@0oYf(3W@WfR9$f9#zh}jR&6{qH|}kYgdFOvFAb*oJf-op@WIh z_xI26h|?J0TjLbZx{9672CX{o%`>e^1dub0QnL4h1#2?Mhdi25q+n1e&zyqm$&a}% zUgpq2T^{{5F|JCZ__p!KQjUOmXBThzi<@manPhp~Jx=@TL0In!vokVwvel0a3ts1# z%~6{`7K~Z#`E(QM4c)hh&cStnu7I0WtD}qiwtBSp-Tinr@~ZvDp1cIV;zCBuN2d-5 z1NM|i)<#zK;V(Laz~L4{?;r5cjO9$dIu=~fZAvu3ijR79l^C24$LxWevOca?|s9 z0l@>ZkVi!$$i% zW89h)SSc`vv7u;lsusju3W*&Peuh^;Z~SO_-CyV4G~NXE&H=lBs^63IxO~~J4f5v~ z4nmsos09EjARTiC6%en?9%y?~a&v!qSEj7DW3OKmaWG(!f}{eqOPk81I%nM&%@MyK z`fX79)U%Rib2HB51z%Xng9|17O?e;K_yzcNn!Bv@v@h>*jOf7cbs&tThIq-oA~O7L zGf7G05`39kJjj?~iWo(*=;oj2M6(6VKLyya{tOd(5M zXrF{ncu@PVZ-oIEF(bGN%JuYO8-IcHQzTEZ0c-jY;?+x!1&Px{hgfHdOdm3l44-bD8#Yq>AD`p$@%cNDJLZ1%zY0$V2&` z@fwKgD;^YiaCSa~v$D>vx^!;&o%k|ix7wTjr<7C&{!o8wzb^H#!$E;fS57?%P?;Kb#S_&v858e=wP+UF z)a(x#%j~JqnB#Uc?~vv(WSnTlZw&25>ihbE;IJna4|fe6?bTsZS5sI__AM^?oNG&K z82~(wens~56j-%iF{uueCiUvyH)el zsxtg9tsV)uhgIyj5u=FDr)Urg-~N64v>_xfZ;jPaWj=1y@cV!hC@ku-)%E zu3^il%*y1%#c|K|QWI()+;41qWT~?8V*)qYqW+%?uxLcOVu#yGo}t}TUGrxzp8cUsLn$?6-A*GTE(bD4Re|mXLz~ZIHgi2k#c#=jzWM%SGM}UvXj( zKmA$9>Kz&cWGCqZW@ILIKu4M4gXGSIj*>iCtWVT{#Nt`;9D2oK=w5o(e~Si@MhHNr z@xb_YPt?$U6-RGQke%30t$w397GJcLERe~m{D7AmMJcHVv?Fr6gh9?=0hQA}W6mIw z-A4V!&&o0h6ngunq~{uNaXHz`3q1zKBMNlmu2Z8k1nlZKmbI5lq3*bHTI{=fXi`6_ z=9le!J3bX8)2LWXO=7JC;x8*E+JGPj`zZI!xy!qOL6Z2xxESq!l*SKb5ZIUsvy9U;f}fS$ zuY`yn5Es)y#dr4RaxGU(HF`TkJo3t{(R!M_z0}LTprUJFKXb&6UFh5QojgZ}v&y+W z>UD(@f7y%E6ViJzu{UB>xMD4-gt1H+H=77Er62*ryG0lI@~6+Ch-q+of6%Cr-R{%$r5>$j9 zCoM7 %2D}b@Uo{L5tL~17kCQ?r3ift;!v^#}iBhYBaw_@BAFG$<-;6QKv+IcBz zJ%m-mt8JgE=)I8^MUJw|%y(4Si}PaFIDm~8(U&?ay`R#H&1Y|r*4G-Y42j$|2Mzw8 zyw-9+f zSs5Nyf+LRTl_)^$e)uvyD&((ohPa4_6!Vpxqw8shKq}zMfie>b+{W*63#xjtEy|s? zatUjFFWiBOa*W0tcXP?!qpCwP16L0CjG`G#>8DFyDGJp27n34BCtNn24C&tQzxKiP zEXq{rGCl;eot&j!!K+Su_k-oecVd&fdBXH?4pb$m(34e3OFWpC06*@4&eLn}{oT*? zTKG;cnN>%Be=naE*3XWWj;;MJ29%z}X2d=D!MB(84_)8COx)TE!!PvFrrXzoe3zRR zpTfPL%8PR5JO+Us6h?UDVOIKgQll4hLaFB`K4~4&9axJrviBZm9U|tnDrBfcNr1T7 zLG74w;i6etNZ*p2R%6)1=529Qb2p~04tpR5AYBi>>P*+ z$@*#BCf5&)^T7CGDF*y*F}P>Jr^*jnv6Nj&E<1A{)TT<(`QQXmSoQn-h?SJWttF}y z-zt~@woCTc#LoM}W{FNsDY)LdG$chpQnW8e;{SnCX!C=Wyl1IWiy9hT#TGW;{43$( zec^eneptMZY+NCnzPYepi}OfGjKV2=B53RUt!w(X{?M&R-N6y9wAh= zLSFizHU|Hm*&h+UMv*ATJ6NL`%SXqcsF>GkuylVE*)0~dEjW|-O6hY*y_wQ=dSG%$ z!Ob6X=%phb-^_fO194N+RjEx9dqL?vUfff42=NUfkkRKEu@uc$#O4qv)*@5-P>w1W z;0ydSKd(EIjQuHB0T@>4Y_=4$Cwocq3Ft?^L{;M|^OAVGPj}GgO)Ynjwch6pmWJuP z=`Tn4AQEC?%6wv$KTqf#-zDcQPm0};GOs0CBvaV^v;unL7hdS0=q&X(6-@;UJR7Gs z$iq_v7j!U$1<-oE6UB9Osa!h^nfJXZYeh;v5($OaJY>wo8fFj~z9gQFHmn z2b6Cd7Nnp`NJ=OU&r_bW2!4tIsr9kAL^h8~SU!m!QJAKK~JQUXhvZH)35~$2(*jU%E!)ZMeCiNir+WW?(NY?=TXZ%#(KZ9eph`Z`(8WY-3l9=U+!?xq+^dJ9xFa@Z@{zJ|@hZQ+TS;JjFeaMES>3feS(n;}rm3d7OK>K_9o(Ml`Eww^QAW1Ow1d<8^{M}-dltFqcXapo3y=bU;JoT# zvq#u9L2v)~WKm#nR~Tk&Em{G4O9}C7l`nt(u%P9IDF|GG+AS+rPMzO+*Cy`pgaHIj;^QvTYaV<>!^3;eyAOZ+*$=!{5gq0H)yZ%3%GM*=2>xDaJ;@msIWkK z^!dhH?QRWBNRHF&v#!uTM@Y|XYmdLO;p;&^t;b2mLvP9ZxQxIzNP9Y~>8`vGewmwR z{b9S3ECHcBVhU-)C+mQ}I0f0ObRpBBMI+r5({J#?f!?drjgwWzE=(jFnUBKYQBB=# ztvNw|;IL5l>AHvqLt99~K{)ch%6c?ywOh(o8{CrnptcjZH?iX_hkS7L_GeZLV>P18 zqQ>DWIVQsP?)-Po9gPM~HmU0w5!|p+pzP;^*ndQ_wFw^nOnR7p=`bUahi#S|Gq+Km1(_-@3?m%O^)-a-^yL1O&R;))Cin>fYrMqyr8nJACFwDe4KCViD}`Z z0z+4Ljs%W#ce3<4?=<-JZ1=%jgp5K$E(Ldz!U)52Sz)9)|D^ukUQa^dR}J>-|R zz`{DZQ~^PXwJ$mN@fT2rhBE0sgyK=ZC& z7EqF#T7rJsuN-{77sQw=rknnA;23`b5@0VeIDW28O;0Q3yFSd~n&-kb^Lax;7P-$1 zPTO6o1jUd*`MVZEHhUd;%~@dqPt-NwK_f%>(CJk5f|6DQGjt4Q} z{+oxxy9X}R+H-YXyn&-?wi<$~MWN1i+_R;xG)I0va#kvc$o?;OyJU6s7ldy9^@bo~ zz8F3lD5%x*PK~b%m zxh$7rM+%#h1+GC93KuSB+M=4R!XevP+T~{iB_{@<>0sr^eRUVMUbc-S7>`Bs` zLM!=OZ04Qc$u>#pgYH9$q?d!%5$@LQUym*T^QzQ0wep90Sh4@F;K9UbA#-$TjVEr| z^On{qN~Z92#k=5T&lRzhOSpL6o}DViF7Yrb%`l^lwHB5T>F)}XtjaI~59dq6%oYUO2E zr+fYYc83OmpVTkTmg4MDdX*xx`u*zKP-)o7+w4BTx#?<8C9S7TXL~{~ZLg*9gQx-b zsVynGGQ6+?-;?up;H*aI>b>(}P)C!OYj+P9PqS(a0oFzgMsk;Soz(4MBM4c34d;5O zq6T1-fs_BRZ^*2z-|Lsv%dL~q6dmuuiO%Ccb_C;6!UB{eFE8lGq`E$A6#Tm{?krri z+S_4xP=^W;OO#ZrO5=3TWUOM}uA;}A^`9&JnV{~a>q5nO=4BDvc6?BCtM6k8kflw8 zt8LSrfAv3=+}Wy17dY(xe$EFP`F&<3%ewAA)YIgO@xt94?sU_1am#FeKab3)>;6(B zkCDA~nO!!~ywpW|bKb^(_;|VBsN4i^uALYtFvqBkO>jFhh;m%c#Z$%5#dZH(H>py1 ze=_=0^!JER@Z}dYRjftLSE147gRT!#Up5qq)2lt@xvaWXD>1~|Bxc4slVMbV#AK~! z-NzHo0J_kwf45@1H3D3!KOg!)Rg&2+EJcK&9vw5D)%(c74}`)wK7)z+-MsEQ(&?BuNYN-~E7Goc!Zf*@bXk{u^K zjoCSpWVgIyk8U38((cvORR=M1ATf88#7GWYI;(0{zfxc6uOr-om0aPT5X>&>*bu#A zSdnLN)w)pc_%o35KwHr|7I3!c!}Ob4OTNf^ht~)-oI_*JU1o=4Se|M+_{eN9Go6-_ zZwP~Y`(s3l5QZxU#063}=JTXN1OVzV3B+5LMvc;ypB9g;A*1sUb~8=OdhHbFas3b~ z{7hMidPZL-r(ucuT;I&O&qKN;tWD2c;i67}d1sJ^?h+X(F|iuUa<>7yvGwFpZl_Ac z0+@vSv(gpGrw_s{13T0O_KQNkEk%sKpfw*}-|870+=2;JIjLc&ZCpub0#ON&)vvle>WtZJ-+5o_$VFa`O4ma>~51mMYH!3 zwE$8Tb?bWkIdKaq9`-I{-^pnA2HfZzUg~-#1TY_($?{wcGqYo=odE82TP z&aT#u3V(n`0M22|*=HOVE=qkh)>QH$WEeyR4FUu+%pp|F@jUTrAS}b#E$opYP28$Q z#A+%Kj}8;Y$MTq1UMtH2w`sznY_`glJbLRtH@NBIN$4D= zw-Nqu?Kv$L}IW9So)*gt{Tw1z4@qXX+2CbRl;d_jUG*evSh*azi-4<-U&ll^oq=}}1V;_fg zg<<9ng@qna2INy8Hmv<0RBw{N9KhjBM6anS7~!=^Q}li4 zk*J9{Vq%`7Bdv~%iy3Z)8%+@9#8D#i(BHzOk*lQQ`{=^OW)3tRuR(Q+$-H2qXiU#_ z2fEUvbA)eXJh7NKP!IXY;LqfdzIYgEmE<3EJs>>dx; zGpRc@OW)F#uReEfpZ6<7+qL|2zqz$50nJ+_Vn1sZm%r2zqEJwHm4d}~hblS`j?@RE zugQ+;Yj+edd^4fzFI>a*<=vyN*@$O)$>rv|E`rEVCC@AF?}sGsrbKfTURd_|e_A$& zS@_y8f4-U;+__#qqt2!9Eh^)C_;d z&tYet-}Fg)cQ%4CC8|Nk>f`5qK*%k+k*V7WdVkyMxQi-=2Lt;kt|6uzr>>cOak; z=7qx?MN*iAu8|_L(%@#p*GR(|RM61@()`0c6wbDLvUW1Trm%qxISFl_w(>Cvx%GF? z7Yu0P=Jc~1NlaY7XOynO&YXJN>Z(;q#SIYJfS7!j`+SI2ed8K-a->!OrLg~tw8EMM~*g6?o?DRWAk+sxfc)=HeNe@cnW zV;>o}>J^0H!$f6v@k@uuKSkkt} zE2cHi2LA-uY&B8@ktK!ylJES5fz-*F_+9XC=HX@90blp=IwC+ZP;-&NH6eFy$vw~W zvbG;K^LLi%EBJD_S?kA)C>lz_{rqf>mE)e3_0sLs1!Ze{}3=+?J`$Ie7%C* zIQ>^|1$FPdbkV(&xAwAgtrdWNtPzg(*L_HX$noQsOxe=wUv}x!&d`I!?BH%$^l z#BQl8{N30kr0ABBO{h7K6S`w6bs;TY%gVcQ;UIMwUXp8G#l#LEZt^R2?-~eJ2KrYa z*4Ls1$K31G-y7JP*Rga-hU_D&$^3}_<;HC|E|aSjmjDvrLWXK7BPaez_tX(aTm4G< z&iRz_OOM|g4c%ohDbBY;-5ax*$@~Ft19P4jed}N zqlaq0_gf%;iQYc?LZ;?;s5mvcdiB1$_YNEKGhSjK=qHqtW=E5AfPk66Uq`Qgx$wS% zLG(9J9ZGyJ_>Zh9!Sjf&o4G3#)2w!dRBdcQJui)9S>Hs*;xHp=a2Me{WuvfB{wfko z+QtMA3}U7d!*xqXi`ZHv(129XY`?eZwmDhmnHjp&Wr8LY6OO2DF`T_?7oyRSF`MiX z?)twXYA*B+)8~jSo%w$M&!{WoK&u~Fj=QU_fbZ_8L(03j0Hm*%zjttWq_Y`Tn6rf5 z*UNl%iw;S|4(ZXa9+O&E|=u(3~|_4Uf)WAKv^ z)%t^bNfaBkP+Wa`Un47&hV;s5)h_c&zVQkzkc--Q)H0Udf40UFkrU;$bu+Hho%^j# zd-&n^eN3!z47y7HAuR)5`^9n9j~$cu7{l4UdjDDduqa5spKiRJjc!oD)nn~8ciA6> z9vzu>a|HG*z2md+mqn~fbmAVd9JD<~2gFgR%^!&2$Lt)?hm{+cZ_66Xp8O?W{CXL* zcKhx6*(y)eX-cMhllSYhmPOhP>Hf7mRU9P_O)^I@LNI>BKX2;$kI46!m(?R>bVEjj z;@8n}#=)sQR~i0kV;PVia=M}mC~i5=S7O)fG^ye^7K(2od^r>4^ zd?yvHp`-xV5L?9`mrL`YoeNKmnYtPqEPf;we*>~0lft2?shOGv3wR_$%qKVU-H2A+-@E*6In$CzIjFaWW+{*901O6ctnnN7}J+K7HGNw8%w>x zMoBlkB{^!LH7hn2rpryYZ1;_ihxEU$*l^hpU{Z*CVmtQaQ6#3Uc=RMV6@I~E2Ne^~ zWlbM_K^0njk{>~T6AO{N3>$+oze^AiHxpjF^kRWx{QV@=S^u;(E7Nq{xmvy&J$b%h z(AgkiDmviSS}AgZmgNm@ajWO^3g{N%A2NG}UM*qv#dpsJL7KPKr}7 zALe^Y9f2{vbjkaMdq(bL6nU5T#`j>FN<~h?jM2<7&IOlnc{7C>*pcS!lj{qSo$%&) z(8U$r^I@_1ia^;-MlS64C*PiEKLJf|%DF8J;YZY#y!!j~$@?d18m@ zUUt#y#%J-=NyYY-N~FRaLC>G+v=W&tq+l5*jZQ<WTQ`v7meKp!L ziRfmZ7Lfl<(E0vYiOAJ;ZcOKwqu2qx<*Vlx*M+o4rcRMeBxUDF;8+kvigV$|O&!#kgTNo|H#wMaz^H;;F+ zXA*WeE`@ecJqC)E{&7}5OxLD|6>Wmt-IwLipYWDiYILi979Y$1-A@jI@%Z%K(LyT> z(rhFlvZO}b?2X)KzBUV!v1JXmftJM7AY!iv(*NfI1Qg1<1347b;sxZX4!R23)+N^? zeLXF|*wyjEKGO zPip*B5$>)pX}J_2P>rEC7Dgs_hI$m~ZHOY!tilW){<_WDftbb0Vslg8Q+|t}cj-uf zSgE(pVIN~#XIXu0%1MktxxP0o=gxn6gx)N|M&flYg@ByLrz6Oc8^dbL%8aD3JWWo| zK>G*MmzKqSy7P5!Go@!Lzg;o|(xrdHOpI7OgrkbhvTT3y!_)-c*84&`N<5yITkh*f z|3_6ZdyvE>L1gVF-fntm#R4D_A;PZ}Fp6#a-C{W~Q-B49-0+JJw)BByVCE&X!0-3~ zQENg{hs+LlVG(e8<&iG8UlqyHLyHWlJ`v6aB5>p4seOeo#=F+xfCiy7h-4>Y$u1@{ z5ZdB;AUejUN2Lv;e}bx>sD3BJgI=h-s_N)bW2TjgC3MbQCSP<0k$?*RBLF37P04J3 z{>ef@TBW;_5{h{0ds#-y`|R1s{&TQS_#HyUI;SUqzj203v1-T|JkoXh(=n&^u0gis z%$(~~;p^K+!eUHL^&Bdi%f*W|ZcT)Xtf{ypjn+X;D@6s2wG!Am?HV1>z3mO#MNBFw z5Zf8Gy=aw0I*TOsle-Zxwa~MLE{_*s088B|;i-m1pY{7+JjOuXo_x@g<2##g#I0wk} z{kc&Ueaw{{M_loe!NKHFVm)ISV_4J@rm!hRPv4-X^Q&~I4zZxQB(h6ZzVn{JDB`GZ zKyUBx}cAt-d;(k+*_Gxz(-bZo~`L zB-nDwBGA|~n_PWJaubX>(t7i%n{S*eYUAq>?TLq9AGq-5YsLZnKz58ArMnTcmg~vw zPKPo2Peeq3?cv7O7${nYsKMOs_<+&7otHIgpqpzzlz5f?T5bl(9ZFX!v>s6T?>1K$ z*S>xa`QrB1xR|BgHpp(w2+H+G@^C+RF&q6C=NY>4_hyS0;gJlwF=}@Wo&S4vSa!>E z6!w7Ya>mnp1NbJ~Xrd2P|GOt;9)F|nLPkRW|Sz5%)E6a|Ev)oeaDs((4 z{AbylDV?i9pMDk;5%N~d?ZD(*4@!&S&r9&q#iCds7CJwPo{(wR(*a(Q837+9msylC zG0wnU(=LyKSqJC%4;-iS6dAzrAU?p;D+nHtUG6HHpjSr~j+*TS=_m^3vVDtWEObCR zH_cW(5u>$kXoY_H&yZ}M#_s(x`>CIEaZgzexzdl(C+T-JupS@~C0`#2O)h#WJc}r! zZYQ%ZSrj7@9PH#E|CxaZI=x#;E-9fB^&cKDZ-lY$viT&E;f)ZteeU>vBd@BEGkAkk!TO`RC7 ze#+BFA+`DK6#3wtWLrN55Prs>eLuu=NAKbZB?J83Z-9?iX|9HW^s255LP=hLPXJMh z{iS-v4D$rXwXb_(h{EK>1}QD_0)>J--E_|E!U1_HhPb47;t+IWg#rn^VA zG0m&aOHZ|`$qg^>B_Bxb1JR8-n}!>l*SbVLg*a=csq|PZR)}8R<++jePUb7n1t<28 z{2+K$Micw0il!{MQ@s9U1OpujAZY!YzmO@d&%j)ni$0w_xb8nPCfgt--Z?A~^%2O1 zOgdQks#bielO5-ARhZr393ZUe4KVdca6TnY-@cdt7k;|3=~6 z#%jI3OKb?2%d(x{aX-BqCwOeM2b>juAR+7$9>>pJ?7)(NWF=(G&$TPkDVm7zgbu_r zcPfn)2N-J+s8RAZwjgUDs%w=L01nsOs}NU_ae|~D1=%mjNy?8snyd6`F2EDi|6ah( z6^$2G`Sg?qh#c6qp+;odO=0(I!7 zj5fJv*O#=>Wo+R;Eq9s)32qiFD{h??br)C-;0|KsEk(!~lgQ$Ibi9cis^ZGq!;oS= zxBD)GadKYidWbwQD11LiTP)n9p2`48ZG&4*cw}~kn3|z0ksCU4ij1>O>$2r9K=~qw zmq$rdn6rk(RL-6jaqnf$OpyC9)tN3Wk)i5Y?(CARMSRbyp8EO^2aD*Pem^2j=S_ds z-&AkfyUA0~OS2hb$<~ou&Agp|L;JCB)#SEk-r*iSXeQg9KZlH!lO%R*rf80O8aPJV z)3y6);+4xDVf#i?e&feagW?Yvyo+>o-{v;8nxU1hc~CK*@0p9w6=V+WBW$ZyvNy5~ z$if0}Q8vm0i=G2o-Asa^V+XyCkZ`#F`t@-fyB`GlkCFr>g#8_?s!@U+k#uo!Bgr@IDT)(tM8JzbzH!S|AezikQCn3LL*7K$Ii z9t4Ihya^!LZ9ho?Nsf)Yw_Kg8Qt;6NU>x;^zq+(!3#nN*M^sg%y%O^6D%&%iiz}=~ zWmn{qt(#b&K5KV(iZeIgCPHfPE3*KKKJm%c2pVe^1itae35?kqnYB=_IYh9F3b3?l z@XT9!O7amvRrH$ZOFn50z}TWPFkc`rArO9GAbRt)I7hhenRfqL*5Z?>XBayL3*F)~ z6QlQ_cV(p9ApG!GSZt>*R7*#|s7HxMnE-+ZA1GC+Kv-!Ji1&mz z5NM9gTZW^;D~<6;h=~COq%1Um{wMzJFzYInik1wXm!(Q&ZYO^aXz(_R2=PDz8Hiz~ z9^{)k>T0)-GP{A1h@X$>nY`GANeD0M4M|AJO}*Zw*Hs#@YYyL&0q#B@Q^x^K{}r(J*z z;QtqwcAfF412LSI^V16rDxM^57zvR=F=B_jsd0o}3ud`|pDwNXu>`1nle%nt|8oP)Gd*V_$9L^Xbn z6X`yPyC2ptc9ukbjhgv2=6ojIeDMqcz7&oXr%%#&q4$pZ&~Paxy8n^y$|w=H6$>t~ z(+yJrCCt5d`w@ZEZ!GyxKQGBmdok0(V%zMxF=@~k1syv~3jTUoP_USGeI9T%6!v!k zQPEu+H;$<6bbjT>!npK;I&wX-wXLPru-Z*j@80zIeK)kaQZAxHx0i3H%=p_2chiKU zHLq-o9SxTpX2U9DK}e^J%=6}^Ole#x7i(iz&8^`^_zY2;M8zeSOU~2nxYp3pIj-_! zk2d!V`VFy5<^AZdo~y3|($9sr)^4o2j|L?_LQe5oZkE6I7yF)MziIBiHq!@m;{;AL z=%)6b9)7wxSNOh-ECI;lrbW4yZ(6pB4qW@tstUNDb(Hj&#W{=feb3%7PE&aJ>G{{C5YTmE^xpFAPGQJN2VRG=CKutTPt3xt z3SkA@SW#~&B@iK|>pGkH$k?~PY|oi;VmeFr^im?aS3H|CgE4~)<*t3CweJt|%rJ1F zJJ^vo2?vS7xB*}UKRa0q$!3pH3x%0Q54C{k6|H{L$ zv*(|%D?Uj=y2*A*C;5f*Ij=R~EEjMJbB(BtWIdeP5#jzq(a@?{K*^GLMua!M?nr4& zLI7y`KUZgq;xhjL52i_^A+YCwsy2(sWNENIqsr!r${4$|K)5Im1eWi_oO@S70i)T) zraeXUkja1}M+C#!HDfjTLJi2Wit(?O0=i+i%XM_RZTbMRSzcW`GZT6J@8rU$@ebtw zbzfxGgfjuqrPSk8QCj}{wFarrv$68BwH$ZQzpg~GcKZc zvt`vfKu4@AWqKgO;!YMTaMM1sJU9@am+eJsdyJ<4>!Ng`wVoV-{w zJ4X)#<#pw7wYPa$amI3hR*CY&c@R`o>5i9&vaAPcu9aLo6|$}L%=F+droW!1@@scL z{9AC@!1rAa-o%&aUp-eoo4KiIUCwn;|CYT&jd$}bqO-7yE0byexA%l>Rqb?XA05GP z1lA#j(<8po0rz_Y@o=EatXwi#|u z_TxFZ>O6V#-W<~+f3vHn50*4-{RRKq&xyT=-K2@OV2fVzXni9FgA0@Zv(~fDUFUWd zR;5Fccl~qrVlW+mRz-_8`ud+=x3Yv%@h3Pkz^?_ngdCf}$v?r*v&bGjX2rOxnM?xZB@osftuDmRzT}$g!|42QZsvO?Ph-`y6kAC zY@xNk;=2xTJVRV31p&46s>jc#j_)?yGkxQ)V;$Qzt6=N0W(|W%z48!>R_P z6jHmIHt4SUh+ear1#NVVwrIA^( zK~f_Qi;HhS=(!5j^zVPz_vWS}vjtMs2X-6x*KzPi-VUL$5i8S)EW!r0S7iUuR^VBK zJN?N?Y$K1OiBknYpmvexvv|izVxH9q6b$9b_CH)a^Ys;NhS6sSFAXK# zcipqy!%R@(Nv$HNL8$gpt4WzB*vA=M!eJJt)&;y#T`!Lkm4R znyRLIA_mQxT*pgGP4Ey+z;;6dWBAurNW*j5_VW^h+b_~TeE)Wp;I`$0`&~;?sKt(S zRam)X4&LmeE3WD3C<#^$$>+kMk|jnASh{NRD!J zWv0w;*%^l%5&JqAmN61`0j^B|h!r5NIQp}3kj1I)c- z*0bJk97;)JDg(aiT&+%2kY{@=g2oHzJ#*EAU%KRlGcqzhm2hkfTHy_BIQVuJ*jd~z zI_l&>rX`CjiSIRyhd|dGnwmcAy~S~aqoUUQD6oPRKaQlus!Kap%R`a8BUnp;-1k4_ zmlUu48x@ZH?suZUW+8bLbVGmLXSM9WpUZQt-aIGSZFwT-tv6KpO+9R2WLdK0ACfhk zh5|n7%g@%8yU539R7IW^iW+tW^W?}-Pb4Q|3~?RX`9`18x(_>GA?Gi%J*w^znBKf- zK{9oyz~~Ce+BVhYN!N9l0`VMnPE$r!;aBi#^SRWe)pOelN}&qrJprZ7tl9Mmun=`rzA{Sotjal`w~Cd+ zT1im27J$Q5JxHG*b+I1C68Vxl0^&*f(v-!k`D?f00vv<+oojOH`D zN0hVQ8e7d2W3_;lQqag@27hMRB0g6*CpR~((?maOIZ;OnV{P`lq8&ly99{%LA?Wyo zTKhM-X%k|pB#1YqWC=Vlg7lIMb4YE+kEqOPKvfGoL8viv)(Ekdq|kn_NIJ|d{7)6= zNS>vEQjYGOD0Ynolg0Em=Cpfj z>hGs->!Y|^l>Ytrw%-SbhQ{7A#h{U46ELZ*_ev0$j^1zh# z=xrs+Wrs{%I5D!lZqa60jN)c#*CVi_j{*oTW)8w};9fOqq>JW+@lz2F< zkg$P}p!*qURD=iy9c3Dm_WlXF` zmh#b>U$Ot$!nLSINBevnLzkHceZdPjlkk>SxG&X)81??Xo9*HyO?dvK!|D9^IEPip z)b1@`G^se~)6jpbF>+lIpOE zd=efTuJrG&Urhz+^B=P|xKRP)VoCE-^w5%YEy7KoQy;*huDV3h?*w4e2pzZzsB$y( zP##cfqpRvVEO?wO>SN-VTB-r;0fhlH;ZoHAKN87VGV!ML&>}bGb~giZaHtX0j5DZ| z#`ykJ@(+Lt(QWtE&%H?w$lpar+Qp58BUS=?WD*HL7qkw>dz&;3^`h=yWy`I z!7*t|L`u2s%b9qn!{InbF^MKubpo8+v#HuPN@c5Js6@Ve#B8b5!MTBm;K4$|j%9jQv2vUG~vB0ej5r)mzMhnD>`4-^oT7r@mKjogu&T!%-QMj^f$n zaef6!`A9@>Oy1KMmBn!8o1&vQ-0(4f<<;wDaT%PyA;?11nxwq~LUx_r0d;8^iJtsU z@L8Zc9bhSaVHv^edqusjYe^P-9=jX*#<#CMGBP5X4svt4J|eKWzQ$7(8w?!Hd?Xp# zBVysyslaz16ubUzTWN*V*zfS4@6%?w>=XHQe{ZRmrx=(t-5L|dYybIcFX?N?5Vf)f zgX<@42e)1xe<>A>Bx>Tnp4|Vh*x@Js(NH|BRyd0rvYId)zkQuH9N%(!9dPocchebw zJsq^p$M+`bd2wlZ?GeEAMw2q;Tdfs_fy1d7uID|a)jn*3DX-H5 z=;+d=@h5L~4CmYG$-F$O*BDp|3`d3+hASzPz$wMM_kzHSaDix+p=lrAnm8+AuzmUD zXqLRc`+v)+Wmb;g6@aTSeq%^ zC@c=$rB=GaCYks#KTw7QfIOpo_4Q2YvS*mdGK$Hmsefv_k|D}f%WTr%wl~H}Kju>R z5PA{r(#%z*&jgj7l|>7)=RZu3Fx`{lSP=1l%dM@+zs*nIs7l{x4rrvMC`-rq8tbG7 zVZK95p?WFOI33Dfe<;@b)6A{HPoKzk@BjVO%m8T2Z<&A78y@aN6+4ig`Bw$1(DL{D zQ5R!;Mn{9SWGDw|sF{tj;a0H8X7e2D=NF>JOe<@2^_>$kU?&iMcan@#kBkAFch(BD zUDrd}h*MF|Nb%f`@HcF29-F`V4kjfllw>J!?2o!k(<;H2D)n5p)B->x*Wj=rTJtIF z2YnC;0zs@dRUv3WJqnjaoZmlHT7!)pAd$C&9kXB#jmJGB7JCbPi?$D=MMNlTkDrO8 zsj-p&10KHU*Uh=JzIxl8`68M5N%K`+ z&z$tLEJf14AH6`h+wm%6m4>;pDDbntw-i1K=sMJ!A4Q$$FSY#^O;JJ()rp$_X_ z@YoI=i3{)}Kq1FAG&D;k3Ro-~Nb~vAz>_(`Ty^eco|U5^ko{N5A6&3E_8p#DH%bba z<-`xYf3aFnRC=o|&Z!)8e_A;!i=({0O8A!EXVvbN9Kp!@)Z9fZ2}(bNT{9G%N_0uu zG3^hNFv>QO;mVzEAPhnOOF9GFOTL6J;gV06P4D}~51ZWn2n3OYnZ2~J;p8}$6a4Xn z!d1v-l7x(Ox|CKN|KZymjjf>d@uXqF70hs+(Rsr|*OW<-M<=jb3MRA@6cCavGea9s zy<@8u_bjtd8J1O--qC=+hQLlW*p25*m2Fmc+DxLnvNDFb#Bz>R6p3h8Zl~A|6r1{E zs%+3Qi)gz<+C4ei!Jc}jEQQCLhK!H&X@(vv|J(3m7J=B>C{o?x6J?lyK0iZF78)~} zI@_3lO3`}c8kCycbf#gYEY*{wQ;tIr_IVEi5+bIyUW#p5Xgl>m-aBY~@qe=b&aJfn z{9Lf}oi5fsuVkL*yDc5#8q7t?mP9>`>^_=WxLGccRt-+w`x1n(%{lz{Zk+RPjlf4c zV3j(4a8nnMS5J*Xba+&%Y8EuqV=-9?jgz2Wt6Odciv(O=82+w*e1L zmy=;yw_e_2V?hW*J&T=TTz58xzPnk6{I!d4#w#6VU|A+kwc0a2-wGJyux6!&zTGa; zvLNpHtUTi;UKAZ>Y5yhdHiIA6z1~OKytFLXNMe2;EAoS8nR0ECa?X}y5dcU@_ONsL09>_`)1f5c zR5??b-w#fB#)^Q>{xf$oX_v&+It)1nkMPZ+9wv2*orUXRC;Rx=W60p0C#>_1Ox=Kb zL4DkteU9DQ+z$H;y6cVUa5epZkR6-x!Mi!S&t)k{CDsdZ8WwO_f!pLXQ~DVu`-9H^ zy!VW$WIn`@ae?6gjUrZribcIEi|{mz^x2;2KLEXIU*DkwV3cC*ucE_zX?=B;l}bTR zk08#RR8LYXJdxj>g2YJwyFQhv?x^dJYVs7wjB{5mwNcg#Ob|g%1Ig`S)a+z8wHYo+ z+i>oRdp0)!noC|YJJ4lJdqFCIDCUh#mWd|+^*N`)O!jRw#bZfv9@8d?av#4m^tN&> z^@a-8+-)*5YJBq7;!Ln(l+K&^g^4%xUbsD3vO)k+2TJ(4^AhTa{}|!+i-S+M3-Xf6 zMxwiT&#i8)-Egt~LOJEn#KDVD_k^!t((o^sFbrRyy4H%R9gEYexEA%~I~)FyU29-B zP~0~Yg?h1lnh)fzMrc}7>+wy@vK1T+@I+>lUl@?HQz+O-=2#xnd;~x54Z>LE$s3C;p>H=w|Q=$4zizvHy^)GJZJV?k53%#2MV8$2HGJN%VP> zj_YUgsim0pSo1p_hcOlt|E$8McZqKZnxXCn@^;d{|I%wbz8u-TcZG}*wU&7kX1{L> z72y#tb?oM1E){NL4huzLoiB1Pr@da~|Gr0JKw8+FKrt#-6c%Vm(plRrQuJf|{tKS} zhYdCwLl5>O9u4&8uF8+?g0nUK5b4C>K*N25V;SGsS1bRSOx92TGnw$wo`<1mh&6hD zehQ1JO4OElsBrkpV2`ZF#QhR^)GdZ>)Zs+OU;H_}3O&4xJlYhKmtMF=H$ZZT^B+0r zrbA9{B06amA1GY+9S(BoxVUJf$vegsQ^5!r4=SF`tzPJ#9%!$ITY0Tmz>60IlLg}G zNT651h&+~^D`@S{QA1_0Mg-EA?;>QS772-T`PyZ~jsMuw*YK$= zdsuAy+H5=I@t+<8=MhvOOb2f|ix0K#yEy>_9Ll2)sR&;y$Z-p20AJTdCFW}o>8DtV z~;umX?L>Te))zaDT zlR|2GRe7sDdxWks55V?=ARHVqkpffUF*$E~%zE@Ozp@wzZmaT^>iemi^G2e@F)62j zf#rc}R>=s-R|JaIrg|$mH{sltS&K$*`IRw}&Bgp}CJCs)IK%krY4z`5=Xt(};nk@* z;*}IGIM#HTN2*=_6RoM14bWziluKMdK%gJ`Mur*`KOO?+2yfrMS$3A?6<7EEfH6~C zrUuo1#_Z>W-U71xc_RIr&Zj}dScG4YRq8t=wTasEC6}bIm9R;<;ltmaRE|Kkq&($f zsS~v(&_$k(+1sO;RdniQYxgA|$O`i~bA)L}e{<^H{Owo&+_r&t{7R3k=Kc4qO_0ud zq$9<(vnF{qyl0-PCbl_Hh-H9+y2AblSj%W>pR^@wwKLHl<{W+3xL%^l>tO(>%Mr_I@JgCRzqu zv|C4^Skf0jqFiF zU7cv*d%yKM5VSWx5bJFf~$m`#Z{0l1M&_EtJ?^Af@CTdM2c-)@* zdfIb(@m#xc^>(?6o$QkS{2Q;%`K9ag6_hoUeu-FdzPY5&4!9cJW9%bl4=TxsIGkh8 z^6oh)%-#AqZ9uC3zxZj9egg$ecRg~mKa7DFA9~Z9_QD}-%={&YwW z8Ac>CJXU0Ii+l>zq1)`8f^Fu28Eei0C)+&(9YuRg?JIRH9xWG*Xhfz_$$9h`U2_kt zaPaF!D!Ntr_t$T=p*s^*uj)P^3M#ge^-Yw0(|N?@wBIT=ku+QEr0%=^u7-u0?vMMNq`HPcQH3R0pcV|a zoFo4m6ZJtp%h86FK@2-786=l<>Wa*suGJDS<6Iq=#~`yo+n$Hsk~a7{4*~(lsX@~( zDPt@H$_>}f2Dl?Jv~aWM08*>Q70l?8 zj3$3esb$UaZ$xFejISy>D)OY(QkGD(Qkd=ev=JYMa;49ze&Vr|JGwN*CFQJH*FP7y zm~OPP%@0Fzu%g8C?uu9jr44Zo0Ze*Q-Yn!dH(M}ixDLuoRXm}%Bl=TN(6aozu4L)- z_xD=S_&XO2Ex+q;TR2XfeNRsh{c%)i4Qx}0-$5J9FDe!DX}$G7ITuvnG5k!yxkbv&g_8d)(_N~xNP=drIQzj*2pg&L z{IBBiGP7cEtMgfjxXVUa6^uY8NWK`wdNFlB?Nd#n5@yVQoX<_o^YdIQhm@;0&*w3= zNuK%8qaWln?7k3*Cap4wu-lp79lsLJ3Zjp_SQTyXc=~U?v}s)zTwlp;&j|srciCOd zj4H)$cb0Y0`2tk&Bw#qH%eZrbC+CCx@{tfkQfsu1pNUR_;NGfx}LEbJBJrjd#jX3H}FT`pkc#1 z}9)XDxZzGCxI?rkzGn1IGm?K zxHb9H{eITuWH+BFLEQrXI+lfjUOs78nLuVnnvq=F9INP(fSCa4tNw9$1rJ# z5m^4yZ-!z}K^XG1na&`G8WV~Z-h_Pav`2iJL<|2^dND$TGWFQMsn^@r_ z>_2I7Ntnru5kWD>ZgGrP%)gE>I2|VW+JCWbB^ZnURP0IqOQ*+Teq!6Uvw6~XyFGF~ zAmr~Cwa(f>WL4w$?k1%cr$4}zqt1A#(k=H%zXGw_<1u#2O3@GC2N=J-=3?f!%hdhb zfZ-i*%QEX(+cXr{+}fT*C_**t9`+BprI+rwwyI_PeNWWhJXDms(Mq_I4|YZA^tL#T zRQ?yy3O)&XxIPcd@~8mB`Tq2=z8?j9Re6=V&V(GhHKTS);?y@3NoCD@=CO0rCU;Yb zpP+y&-#R(JK?Q0A>{au3>|*7f4$V`h-8^H$v{Z%iGGmxsZ-~}0Ie?1g(|6bTr#f;s zDPNS?q1)G)6*{VIN`j>T?N$C*B;nol+uj{N)WkVc-xG?mu_dn+k;2z^i{XfdfhjIjsM@|3cWfwA}{h7|i0+n~CDr@Dc4d&+wQy=HpM1KH_=@hSX5SH+&QmU&V^?*|6IM6rU z`*x0ll6jLulbvNh^j08T$8uF{rr>|wODsI@ke6*%VtpT9NUB>YbLleZerEUO0I-37 zD&HTSX6l@XU}pQpp8wrmv{z>y{<{D`7C@zxx5k-<=5>{STHmODt=h((mN@NGH+G30WPNpdG{t`0L$j< z@n$Nu32>yjvaW?S2Mg54Gi|!{xo?jAPOwF9&tl;jz`F-Z6MfGM7-$*%Vuu{?L0dfC%}$C z1K8kKw>gs>#X3W&aPvCFsBM?p4?RQn4LN4xqw0~~xd1kZ$?dwIXiGvvT9NAJ5v%OU^%od!WMPCuJ-OWYXxAzD!|sEyhhCT8%cf`{78{fD%Z~B6 z!ie&4pAX^hCa8M`SY1q=+d!Xn$?_;j0lCCyp?$kl8)D)ujx#20Oh~}QWa;$B$(o;F z3145oSs0);Mkfi;H6@Y(PQ83Pk}1qvvguNN4ql^_Ip%W7Qx-)6KLT^+<_pr-T}j&r zpl-OsRVMC3MwTA@PP;LG1w9|i$dY=Ejs(pk8 z_Ye97gtTrLRZ@?HExmijm}>%jZ< zVvhVq6U3XVjp+^#t`M2leQvR#?(=~#W9#iuhjYb&>(7!GBQTibMaP*mH9lm|L`f$* zDSFq1xY6N>o8|JcxNAA#VQqqD9nq->i0j=A{I&OUmARo97g&FKk*E`KbKP;a@=)}i zfF!!xFHCPgt`dEwRY~`sOYo^nk?W@0d6OGz-9+^Fs3#Vp?*l zatACol;EcxmR6Oo>>r}a-rlfo(539DaeA3reMJuI{LdSj6{ebj9NXQ#^b2c5DgKv4 z3kzMrcD@L^>hT;2J>Trn8n{Wixq3#VYeD%!%?RXY?%B^H+09J08b*XxYDI#saf+*{1mg0~o#4aZQD4O`7myJ8R1uA?uR zM!y(IK}0k%x>ri91W%KI(=^CR(++od!twN@wWBpsR&CFohHoUa5S_uG)#-K6_0 z^rps<-=4787v_)ECUj zE2`$fgWHmUSs0IkSI6Tb98O7?bmasC?d`ca&Bp6dgJ)-NvxiK0NCYaCBvO>_)p|?qNuhp=4Us+z$9P8@Jn_`6*|ZhDF*iqGOz_ zBZj967&dwSKsKiz?5b|Fht>m70r>q!;Wo7|r6k4GHz*K#q+-6Ip}%&gyEhwdYrWn& z*r7Pb1{WsN#cwK|^Gj4eWqkbWpmnY%+cJKqIXGU$ZCMJCX{XMwmV+t?6~CKX9U7|z zf7vjiq{9LZ0Easc(OQI(u^fOl;m5DEsEa%ASqO#AeMW|j=wF@fI-+5?UB|<)%)`vA zdQ(aGy0^R`@^I;za1?KSwF!RWd)T~=?a&|49k}Hg?KTGu zCER?BC*rM>QZ;@YAwH0Iju8K5#HZn@43`=_!U6{6VTvKgKFFHP)`lgR0h;Fg4krPJ2s)cJo3lqQK={y*Myz)41+GVMDSR2 zsMY!2B5OtK8bn;7lW)_66p~b5)y*#X@OSCDQh2nFdhJEi?A+WvDw{of$4)w!XDQFy--A)iqEi^rniR6FulzG7HR;S%dob`1KqEkj z2~);8>8)pzIs*4qn03UlO7g4g@;n4k+Y2VJUQqSfFBV6<*V|F+fyDUg(UJ7sbFH8m zs%hQd-LLjN5+8J9elLZjv@`h^(KLL!IE;}(M8NbZrHIBBgQqS_`*=hbZLh6})=Fl1$E?Vt34X0g#X^v<&;ft(`XxtnaQOQa1w6);k;hP(+&^%B>CZ>iol~Y0% zF$6IO1UTr|uSTuU3V!}&#YhqISbbSmY)?U2LyPLV33j3S#H(S<>tJ4fZdVGmo^wJN2P_gHTZ zgjcxHm$8gO@z$YN7Nl^b#iuvN#)D(~R04hH9{A+IqKp1`^`@Xd&7>q^#GKxWBr*im6h`*R=z$WW9i0XCHv}t?l5S?L+paMYmLu! z@I9Q?LOQf~5@xLf#wnA-niY8}1m9R6r!!h*w>DIU;5F|3)Wo5wca2PXcf`;Ib{A9V zYm1MS%!9R1e{8w;Vud%sBaD9KAot|QwZ~V>bw~7(v{yoH*Ljy3#FDiV+4x;Vdss)v z^w)JHOh?z6kp!l-jtaQKoO^_BT6ZF^XZZ(@l@-uLU#JUYx%-NdUtYl^k<-ej3;$C= z*5=D4dVRwq0!^G36B9so6U4;v{$aa|EBiHnD`H00=f?Hd*U{&vSJiW+VTY?w?i*g| z+Tpxoj}ib8FOAYlSgzn5DTKj}PCLP~HzbJa51#<{$ygf8Qc7yI)t8+oGH39REqn0s z4(YMCKF~tRL=o6Nb8RIFd*;OE@x)h@Wb#q5pTQXqZunW}vz2dJsT4;kPcxFTpMCg1 z<`oHco-Q|I{iOQIHC*_}%{4^gbs*k=6jVDv-l7(0o4jk}31R-b5iKT_{}>Q>ez0h} zSf5A-i2-OW7{1DKUqVnk%a!R1xW;2jXs@wdLevGKTFbG?(a6M4)=us10Q1Q9yx zsJIHR`IndPUyNAaNi=Ls zBTUh&3BY|{Z$AiU@75yYZJNN$e6hF&AQCV7gCOv<%#U2Klk zyHz2XYpPbP5%}YXkL>gPDatOLWXvBjxs+<)tXWd|OeV?q)d!$B=myn8-Ko>6|Iy@9ZL z!b2xe1g8asSU@{frw3|NafP`u$bL&P1S3*qcKZsuR4qjPkCRp`c)L^rasJm6OLG2+ zn|L(rc`>RKeN(VuoWY}#;qGqX))ZtSv2;!Rnd%=@dnL1qT|K?#7`Y;3tsdSe5*3MU zZ2`fuZ(18)0A?KB@xRNNk+Rnh(yKusL1(2_Tvgf|9q%{oT7D{(!@UQ8x5{urYz)7J zrgK^sD_fSJbc5I*SpNJ;I7wAv4Wd1NsLLW&rw}#Lrf>hyn8%~(eeDp8xO{VwXYWHR zmJd*UcWDg#=MPc;QY80(vj8GusXl4mmrW+MEqesl%8Nse-jOKrSu)S9w#r1v-J0<+`ph0iVlHF~2{2Z7hO zwdj=})x0KnD`Qi^eZ-&=7&iltKQbrG8?Nl{XcPnVteTalRs+n#^D?o z&rLh|P81=S=C5C$A3K12CRzyVY!D7Y`&0P z=mol&RjwOmWzcpPQbDG+nE@j7GGAU)8DbI#Zn^xIWLIhbCh`Lj4tQSXM*~W{&%&|A z1j+u$u$(j(F%Yq?H>2+$`5?`nOGVXQ5NBC>p`w+23s8~F&eq*Ht1?K&E`JEK5C)dpQ`rrKiM96Rx~TTzpybC^A&RTT2^wlwQ)DuED`_FS|rZHEQ6FW%C6oTE*t%EMQc{RJrCUwyyAgu1}loe%hPV72Ha>w=`@ zBd>cLUir57+!2@%M~G+lgZe2Est^YdX*FE(J-fw^XHkc{pTI#z*coLG(gGBikW3O} zj#T5V%7H?byNDdSjwE$tIgH)sUK^y@DZI4`UFEU)&NvQ#g=c|bl@mX4H=JCdM_j`9 zaarWOi$5NBdn?{Abr@)BK%1QDK`fnv6Qdf6WzQI2E$tgbA(P`wu-U>J+0W0p376fy zq#_?G(Yb7085{o7#i5|i2n?KtGw@kRb~VC%xA zCNNXzop1{FN08Rw*>jwu7aqBDsrR|i%O`q3#u93eJn(N0D+Z<2n7&?$wre}N>V_;2 ztZFguNWIE=bCo=Zz22{kK;J}GmT-og6dn7Q;nuNNc*5JOc!PIHwOuhquK$Qv%9dH& zx4WX5Hlwv+!ZZ++W#MN>C)Q0T=O;?Nt3x~-^g1_R=O>de`hdZn236xxvSZRC=X^3L ziUlTS%<+FsKP<}4sG~ev-%~jQ!`vh=F8AXdqyWX96#MVa$E@;>6W@!Zq7!-ZgJ$y{ zU6PU1g9-I2==@O7IH2239|3x=w~?C-#&9aVpV7~y{dXQoLVlj=69rn#oqU2f&Cemd zM*`CecP3z-+gM2@KB;>IPaQ#gTyP@cskH=%O*KpkQ4dO%o_*Ih#R92U{RQIm613BV znCBhg*1uTedeb*%gXpLrAh;H#h*1^%hzW12bz3OE zXb<5ChSPxf@$k(8176RQbXTYDOKGW}cK-v=n?hBg6Z2wt9)qb)H=XRy z+JU=njFfPUeyVhQeMBrts>N+?nJTe~Jih6?SJk=`z7Kq9ySQ(KIC=w(mmfKL7@q1| zucdP(G~c1}6#3b2p>cWlL&01FQ_r{i>}fiSIVJm6i=09G=Uz3KiKG)~sZzg@d|{9S z12D>yk44uX;LJyp7Cv)Nvcn1H;%qJ&StoJaOG*;Wno~cOh)tqQ)cN|N34@xf!+6}9 z@o=_*qjzR^EOZR9iQxo&SRzSK&yHMpm_djMwRpTSw$`9qw^B+*=JS2S_MEfR?3+Z} z%84=A;??$kx&{A2K1u4?x8OmeSmt`1tTomtWuz7PEh^padwDtQ!te#&pzdJx>X(Up z?}&%e(kX6dfAXpne=sorp&^p0MKKK|LkVi2^vnP>P|CnE;L^m7k?-rG1Iq+*x`-S6 zSEyo#s=utoLifI#pv8(|e-n?|&g1i(yfV4bl{^RCJ3k94pXQy`9w8juX4Vh{UG7M{2&wh6H6 zaJbUuBNwsd$ihjxA{T~JT!Qri3m6%*2_318Zkr5J%lzyk#NYc z2DoeihU?%$b_s>&$W6DKck0V8Py247ztu`bVD#Tlt&wVJQD&~aXZ|%<=rMFe7MFNF6TVowgFyZw=blM{~Y6oQva#**`pd62T8= zN#<_^$&hb>rASHY<&WB zWR?%)sls?p_svxWdFD-uDsz?E@(BAri<>iEH`GSJN=0(3$sEI#pFL|U?irT@{o+yz z5m30?>MRf9^w_9`<>6Wq|>UN%RX#@vXtgqCUMS z#(8B&%p<%P4LwOPGo3(;nE@nD?-wH#d~>Ylk8Yh&HE$#IF0W@gdGpWa`sNo|PCETeu72Ir)MKVmb}v!C zxh-#y3Eieh4vz4rWY9@_bGv1;9;fZXs9C^sD4F%Npt_EF$wUMda_y%Qj}2+vI4>j+ z{~cqIINaa;?)m73)b$=mBfxSL3UA6F}Rt;O8cJ6AVxAZtlJSZTh~K*ilw37nh`&K+%jMQoxvRy038?`cXMFH9O>C7RaI(< ze6$K!PIzas;!ejo^a$=vBK=*|T}>@=|8TX%j}mk~D+Tbr13rT6&UrC4I}l3mU<4l3 zy~PzdZi`D!hRC_Lq%vDwX{T00v-UgVr*B8R2(OAjtlfl4xWobM4lLlmFQcX zC#k$h>bN6cqK>(HME4Ssf<^%Eu^dOGb05WrN&5JLtQRV#z% zsHgx{5h^)0C8R0HU+oyCgdX$P?P^RN=5ba7LrIt@P8)HlzXAv?u;#S{#is!XJH4j% zcBbKIlhis1%N;A|d#|lK79LX5)e49s&{@qSpLQSB?=|3Feg9;O*D6_QX(Sh{i*F;B z!9Af3chO}!Q~8RNOp)28I8^$GQ<<(jyK~G!JZbus;2%6E537BEb`jqP%;Awl(O3lx2ii{XTf=Jyhs)(jQ&`ymnG+4` za5B1v0Ku->ocwfzM9L~2`_nubRrC`0+<*nl?Wmky%_qkDmuj|*xz*lvRnW^%qny1o6 zV-Jg_--o3fK;0+S!liFgt*K3{VBgn~2m8AwOT}No1YHQ+Ab2g}tp56PoVeGw`kfr( z)#i1RQq!qD!mTlB-Au&Gm|k9Yc%}H<9@JK}bQcVEfr^2);j-Y(ot0ysvWuo1l*wikLs|yO%%%FUu&_07z6+Axig6$pmB+q* zL+%D>G*VYbD3EkSd^);63FVtH6zAn#kBsu)pQ|gFBh~$J!E18x5HU}~A(b{)TUn{& zys|->DRf@(*{aq?e7Ripid0i^Vcc#<9pm}TuB}}JU}3ytgE?ydK)&~6dGF)iPekdN zvRtSXFa4lDVD6ilV(MEjVdiSXK7o&jPewH%WHKi&_j6H}(1_VTubTG{e)=3b6tmF(2G6=U#nt#=stvCL!hxaf;N&%@34au_LI zrzS=;YVqjKLI4@O60!(A&>#al@6n64)K5Jtei=;gu^>%tT}#VS$saZ|19x;Sl1?%* z$9AVGq;&^_U7Jj{{kNZkFh_0YSQp$dOJoW3O&_3qO2bk@T9~!&gv7wnG}Vzb)r{46 zVuE8}#Sr*fAm?S=G5p)SVYfLQBjkcZ2BORB?yTD&TmbCaT80e0-e2|L4!gPtMsXh&X3W}xyUGyd8@3$h=Oxx-I|-+(y3`XLv~wbGFmU?4 zKgU}VPu$C5jfX3BF4Hf!1I5b@cBt>C3k3FNLB%oTGaX87Jkh=qyF2?v*(NH>naZqz z=7`Q2UXp*hi8Vt~W>kreQ#`p-bk92rZnxO*JoKcKf1UJ$EV%z}**dU!OI(G z@2+oDGIbOWH%X^1`);|!*RC9^?xk7Q*XumA85As^)-(j3{+fBjD_))06~9ix2lK`) z<`YaJrpAOOPwz&v?!2vA-`S_!-{-WA--|Yr&hazETGrc_0&VM~ePt53X5@-PP{B!u zDOdnPFEa0;gV_Y?PrAa^Iimx)cJ{lS0H*-u`Tfs-nAME+Dp;|Hb_k#C!!O=Bq+uz0=lJ32*1#gRsiv-*4cL$oI?O)mGhtNXW*j5qBkW>rA}_KnxUwdt9}1_TGul+`1&3!w3PW7#)29XTRQ=3rG-f5FR)w zAiMjvTm<0CqXVd{Pzf{~^c!WS*MY1Y97lH){AD&L57cu6PgEhY9|>baLamhRr{VL? zg7kW%=Qv#7c7ciC;CIjd4Gq%g!J>!4qvZm9&G^4Vpm4>3V&M$?cFRn!=C^i(a(Iq2 z2kWpf8BZJZdJOnI&<|KvEX0;TF}kYol*`00cMaBEbDL+V8WaLVCjqg*03f_5#O~p2 zk+|`fv~NuLZ#6VZ*DuS9`9_XD3M$YL-^Ijs%q-`jbeP*0oK=RR=Ge|2b=nPbMlT+v zyh&S1nj_Hw$FR#pgo8e=k@nmRD3K8ch|FkdFF$5_aM$zW2Um_h0j9Q^bAN_LH^0A> zq*A<1-mgp?nV=xd8fir$^LtgVH?oNQdul+}rl0dQDJ|z?*)C7rYuc9|oKY3KdU#0J zU6fQ9*?M|nPR1F;;J$`)rY?D{qPE+aGXc^P5+BvL0!`@yXLh)jksBBG;Uvn9+Kiwg zG1N2WxU)xxU%;xC%5FP%(jf0ujc7IFcE4)XFxA2B;=Y?c-h2SGLG?Zk(Pre*lZr-d#*sUw>JaxH4ijw@+UBQ?1_gmG0AlB`={b7-OL!j1W8BLLC! zVnFvOldZhe!)*3K_RE#nrpC?gss%UpGGMGXaS4ehJVayH&s&Bk0(kTQg&%s}_c+aM z=@0K?3vo~{)$&xGy`vhVM{&UkI0YyURSF{ zBfU}cj}2qg$2sRKr2%Hcq9I8a7S2~= zmlx=t5{}+}PGUvWytE1WASEr8?jzx13$@AQ z=AxruS@?dWM`M517C61@`Dfg=tDJ-wUJ>pS`zJ`nJ0dAxye2$?=3{pJ!H+e8aj61~ znXYx$_?^-hdkv$44Dp)~9ThRUuRexDzzobZ#my7;U#-kvm@D5q9b_PG*Mq`;0?|o~ zd-+*_n47rEeJ;&6D&`-;O+n0VT=nT$U5*STruxL}0Pe*;J%PyR zKw1_Muz;$UCQuL=CZX^54WIp$N3zeO#Z_d&^Ily|%a7n>72#sB*IJ%z=l2Qs8w zg{wvKxLmzf#T}F={uwR%3Zf1!JK^;rTEPZ>{O^ex5toLKY5EKIcfW6wgaU5|cy!o% zFVRaSqI@I}j{?2iac}DL*cnHxh}y``#IyD!V-?U%;1tiy?|rS<1<2oD`QjErl%A^4 z-G%);jekiL&6XJbj|JGAuN-IZ%RnR-LNYa~@UFem1ZZ93No{G_EbAy{sy*xd`o?O@`;&p?Am8$`|q#^_5BR5;?u!)_&L4=i|o#6O* z*vl4Nf5Fr4>W-bJcxO_rUP6S@@zb^RvE~Vem}CsbXV0&j)Z;Gtc0p!v&#e7sh`#V| zWz({4jl?Y{;QB|gHHWWa?bB!d4hzMq14dy9`s2n`Tpyk9eG{#}8M3*u8=*Rs^0#Wa z1#3<_r0mEVfIV9k^p2Co;IFW;mm%EGP6~u`IpOBIe@``3P7?QXnS>DW#e@fZ2k}eI zitPp}SIUKP4biP{uK8_k3O530;ye7icB12tp6f#io3C%?6acy@%Fn*GzaVJcBr`T^ z{LMAswjdd1+_Mq%ND(9qHkaOnmL3!@29+hPL@yGm@!rF0RBvo7JEQqX*(+}bn%awk zeEiS%@UGZFOsJB=ztxApRT&PG>+*`+jZ(~62jO(%>?ArKlaT49)M@3J(@J;Ucd%GR zYoqr+UigYAxW)#9Jl&oY- z1w?c0%3Ie83bVdwMGJ5W z&LeX4$Ocf>hK_1|q#S-;d5;lYcbPo+P8)D1Xva{Bf`51meEviCn3oA%VxS}7(l~BF zLM0%^{TLCXDX5c_SCTg1N)`O3jo;`Yba+k(F#1#9wJO=%_f&A}^Fi7j5Ce!aNm1PM zOBNc4HU+(YbuWtXpXA{9H*ex-HVrai7JilfjP3XB6B{x{pz76I%IM6VyXF+Df(90Q zb0B0nqp~B|U32vf5ZN1#7IT3PQC3_U&3meiQRfGi@iM&Wpq}C-(K}=PVU$jU6?ncL zbw#p3OGA@UC~@+l)0vn1%h^Rv5WM8b^*kV9(%6fJfp=yDb_N;A-1O45r})geM_X1I zc_(GV^w{k2%MN;rqJ<|kEVfD*dKpBhU6}O8LH1~8gqM6R!gSzoT10Lj|F9vC?|9kK ztFBN3kk)}!-4#<7_{#paQocBDfZQ#S^!@(Fuc}X(E_{40GmbR~XZCA}x%l_~$6Z0g z8G)X8CNBRT8}u4DT4h_Ul@(jMUSIT&Msy=@uZJ(>9y&ZZk;cz^e=QwI)B-nP*yZoP^~2|#$}x0lZaa`?2C`6-tYZlJh_u7?;}fs})2~s( z9waRNw*~@l6Y=N%7dz3p*FPNFUw@Km|9e2WE3u59Y=Sj45Bx3aQx4h4)T)9jd8EW) zWNv=CiohCrKUJg%?G?KbxnFa{)AqA5qQ{iJDGf4>7XhqIIh#U{7T2m#|1Kfm4s9HL zM9H6du7#C2rw-3~%r$OsY%DaiQ+#Z!*jveTNf~#225;wLL~}6%)QN(31Y-FVtVap{ zCwLxf)C)3pr?k}jHNtsBh0|f^2D2_Gpazkn+Rgwh*!+=IHE~z|;mfO}e72v41UF|7 zkH>pU_XGqW|EvRg9o9m1F4)*v7`|6F-BiBbUvU_OTp-(9(RPNlCG;i&voIJex68&2 zF+fc<<<9uRgJDzT%cYU{e$6QjG3JW&YUDTboV z3(3v%4%d{4uwchEVV2?Uq=dk+)3;SN;lXGVRn10w7d`LMguS$zuCSgPCMjO&pDNB3 zaXO_jPm!LBMs5G5J!P^hZ$Nb)5+sc|l~o z1DWMh1GYxaPNgYr$`VTdZ=;2w{!-1=mYt3wq9svvzJ`O-Gbz%A1$cdAv0r#GIO!bhgLjw5pxVV=@!H)wzL=rJ9BJ577i2a<>7`|*~ zlIZ0F_(G|7GtXrbfp6}4XnNoAG)OVYER!>@peK$}ZAkt(dDZUNoS49m1UnCqDiD(y2amnQ)Fcia>tde zWU3aWH>O`5%7#y4ygJ z%h0Nf9ZfYndCw@?$yfxxgtC!68ywBF%qqYb#{OC0?YAD;7Wy{t5h15nzWe&eDY zgRj(U7e;&6o(2tWF_N=yUn}D#QKoqxz{8#Uy~>;(EeE=0sSWcVuM|L)Pbi%knscuR z%FHX*IewqoLj7S_8~Ax|-Gk%c-W^`>g-5Z5h%IT z=XhRy>L{{8cz-Q+cdEQ%r&nUYY>c)LU|m7A_3nbYS)t;|&C(94S%p0I^pXR1U7cTC zt$b6#FdBWGYDlDAwQTPWZ#j~q@m|Mo%%aTRrszqJtrc*jk z&84)#6<2dfbz&|vQJmK2QK_HcZ8(e$k7Y|p5~`#Nd7`okGu{Mj`)LTx4sN_&+gB#! z9wqHb-Qq)za1F=pJ2%eQpO~BFx;-0qnJMK(K9A6o9UJ?Lb*;+WD{!aS%F&OU$pKLE zL5{2@BRYEHp$H-V7FS$}pARkk-R`Z(54VtXg^%Hh*UrN*JMReVJMm}NH*4p6=XbR73_=Er(bT) z`%}}>&dVd->B*smadtQnT5b_>T7Q!7naR{rt1JzCnrndq0s{0KLb z1G?3i-`aK2OQ)}*yKcR)fu?UO8QY}qBictkdWS$z{GX8BKg4Fphjpfhd(5(4h}%Af zezB@WE=!*eb$yfGR&`5bwRHbg(PBgcv0@)nu83xVKAn5+BrmDD`sq$@)+t^eLkP%hM0MBE4uY%^p^wrurN3S z(eYghC_^*95~RqZ!%ZuIYo_XNBWj3Z(qREs_EINxt$3fdB@%yo-SlGX^xM`>a#V1U;dni;zhECHlIb`oZ`HQ}}%iMQm%PRPz*9Y;aRa~PvFZr?a-F5}fV<>hV6RH-F ziSpp~@w!bKGJ=M*oEJ3rK5O&7oth7w#+jfl#)=jcXRabKTkG5Lj7>{Zrc0<|iq&3B z{n1-9JH_l!)OVn)naCbt*yhH}e^<(6zSff-))(K2##;y9Bni0p?xT%DLqntJ;kP#y z6M-SY-j=tM`UkG1`1y^Y#aY}6O1KnYy?(QCu+e{#c}csX{Joy1<-QwDGeA2jYfhDq zjz!2>#gpWz^AKr;lMA@g1Zo{y@irF{XzM)Ekm>H-u;t7l1t2YHHMZ|rTYEfoAkXW= zW86}r05J#Z5Y^AU+$ejar;|(layt6syLVdAT}!+~a^BPhEY^jQ*&F8D5q=nsi-Se` zL0u^4YPCw-rZ3<1rz*-~!fGZp6%kj{?4(rsVZv zw94cz5#OZa_t|j9Y>GkvM z-3lwY0wiilxO=9#sd{!$xzc9$&eK2NRuxxKl?_HXFD^3L-N@aHG5)(r)kS$m%g0d* zsSY|V<(DefP(dG(=E6{F(CZiqkc`EAuV0pGv|VABl{&`gH%$FG~|mJ(iR zMsLFy3-&)O6guV?>PYMPz}GZ(*V%J$O6==b=T@xUR~FS}M`qJaT~MNZ7@=FHTdZT_ zKr{DUZm%vJUY&GcR(iNNjK}S|R>?TLhuP$oB9XtBKrgm*vl4Szjl9*5nZ*xhZ9;Fi zcHsYYm08lz;81v>B`_2|a3ogw4~rE(o_#@NnM0Qm<_C`jtPFJx*{ZSwY@1+hRTbBZBM4+9Ug1^_2^G;_7JwgUXo3lWZHpq<2k8htu)3TbKS zw6fXN+7wcf%w1E5NOOsg;VNqTALW?biValA-ei^0)3tl`pOUlDC8^bvB8a+D=uM@^ z>qtcz-;itTLIs}h2y0aQSX_v>C*q_h6QyVJK3Heeve8AHT$To)PAv?uENuVXfPi`v z6(^Db&`}%!aXBOsZPxp`u|-spwlPA--h^U7n*Z|b%kKN0xR2O8JYV6G0}xOPsjg%H z4FhEBj8qz5M9^>;R{cFUcG~PXI8by$GkuQdd6Ec1^i8?Gk0LAT@koeb@sT^u8T(9c zC)Mz8JJ~9T~Z1Yv$ z^G;?yZnE;Q9}5|!bUXbCzuCEz6zCY^y$9%+KZ+bE9nY(i=ex?B^yfI}+n8ljiZh=N z#SASDEnZt4`E_u~US1&sz@AUK1V-Is<7F+CPp46rrzcp`^b4dnBj9G;P+<39^1Aq} z9ga_h1*-|}KP@Xm(F-v{k_M!F`cF((GmpN zcLbw8YbSLg6rhYp5F&e{MIN=IDyueaqgSI#Ovujs{58*7{U)k@tGAOy)OEOJ=D@(9 zpDt!A-XBaax0AyCbALy%%Ln%(xb$fFNzlYqb};Itjmx5D#;oTJlwW#jWWfz8>&`^k zGM*!ywj2uff)KPU9o_Xd83~cgCKvCeaELCb?G9a?Xk7Yj33Jv)vQJ%H*cRF7d}pFP zi>otw-7s1>u$qHWG9}7Tr3N7)UR^Lp%r~e<)RiC{<^)C*JKRyQxO+40H9Ww?%I0F& zx2YiglUXN!=yolg-KLIF3({i@A?(7eMSSn_c*Y8&_fDho1AAkW(4~w&bU0PO!i)jx zp3Rjg2{+fkMl(4BQEi62{gTv`PR^$*Gsas0W2s)ZWLy*C*0NXgW%5MM*PjnqEiv+?=1 zTR4hSXy7mIK@I~jOKXj8f_AyJJ?9y7b-Bl4>y-iynQ6ZGk*k-7)(&_-j zEQOi3yJzkN_Upme@7l&s+3|`Vi!3IVM~i38hUd?v@1WgAz!~o{3@5nTP9Jj!O(#r# z|2*%qh2kY`z!1*%UZe0Adq--w=yU~TS$G<%Ywxz&CKr1?@X9(@7NyX6vRG*1-i;`6 zJF~N%#IFp6Cw7js|MQp4JXm`Pu9@wdub_p|I!WXEBX1W>P=ao$ia#!uR|tVYPwNjx zhGvH@pULHlRst@rPA_teCHZuU42+F;y zI|T!qm|K7POe?#nB)_|p7u(*E5^bnb4FEB*>{-{(?0ezZjf4d(up;CB#wz8yR;>M3w?r~+aw?YT6G4x<%_K)4kz8RR@9Paxwm%9k z(2!2w)%6<3UAy|bO$x2%%q^vmMEm=3TM~Vwc|4(d-o(}gtc^F6!f|0;Eit=>wLc{Ue}JKtc-8}0yaOMl+X4 zmn$gU=?z=Xb~3N-h^{$djzsPQ>2neRBqU&nruEAv{1*xPB5VphZD5oy zslZCZB}s9^rscGzyURUW+HZe{#y12|*vy$t+pf2PgRqp;La6xHZ&I6O0WCD#yQ z9qE637LS3S`=4D`3i;qq@V~Cvj$rMm6TJFk&r)wd-x}PT>RxohVl=DXf-SEab68HrCq0P zk7Kf~VG}=HYnSdS3)xdMlFvUv#08Vr5aVrk6f`t3sh}pE+A?>jkY$@$fK8Jw{|<}-NrbK=ZOlSL z?#c5w{7Dkdclr*@5q)(>Sm@9EBR;ff ztrIFu?;&zaTT&g-zmNFDTf)TT{ogw09>y6DmB0%Rts7h#N}H*F5z7}=^k$@cbFuuP zY0VeTbMY*!nZ=-6MI<{e;cE+^FgM_5F``YG$T30@Y$^ zYIsB=d6c5%LJL`Rd8PE=^uR%Y{q9th>RwM`W;4_#{R0%2doFYRD=2zm&oH=DK9n2q6yq5bx_>tr z18BAW#F(j4t`^cYM+R3#{`XrE(OTTCYxm5J6tF2E+)+_6LZ^eA#qIZAXeleif>SNPrprzA{m$D4fu$2n-ZpEUi10#>M>GC#E zIAtR>U^Sdp*_oRbP3p@Sa)0k+BZVg#w~yn=(#CPGMGQtu} zl#&jn6zs##VTgCya{ATCCgd;}UH3gl_9tYXU8C10R);RHf|LXj=o%Ilnme|m{r7hD z`DH}N^@Ta7(-2?90Lc_-HRPj``<{Bk=w>*{?a2MSM@6B4o~b)bLyqJ$e@x_vEn8lV zoe)_>GA8}nr`_9ZBC8)@jJ1+_EsQ=31lFaa#l6(vX@4Iay>lU@KHj-!gzn9s@VrfN zUyHb0x_99k_Wa92TSMVPDuKQuE$e?#p1oTp9~WULMTLL;;ahcGt*kztUM{?njlS4` ziLq!Q3@z3tuIVYvZ{@I^>-fK$}rOge2awFhs3=v*>o!mlR5z8fp0oGA5NYZ_~sVkXiszn(kKOoKxLvLn#?T@;{M z3ZPT}PR1P0j*#`7NEkud|9l`|{&?CpWSPhI@^HCz+l|Rc0EUJ`S(CLFB7cvj%H$h@wq;5XZ(SVs zGD{$Q;1xjkCX|DNLt2f02!MA^zK2wHD@BI!zlN~Z$FtMxWhiu(Ad8#gK9>5_ohLu| z!L7zGxcWd4ie4>QJ!!TT_`9;RU`1hokvj z&!d2I>wF`8mDsNdS>&M2BocsAKmw&H?t5f@aJfoQm8fOlamE*s0ldZe+b_ld4$n-+ zIW=<1o5B@-iNO%<@x-h3+CU#a1(#b#!M{i>Mrj;pn z88Tk$^euIiy30QP$eN8g&YHPQnKW^rn&U{;31GY?HEayb);!f5axp(nJFuM?351-~ zxmE7h@>MZ`JYsRVB7EXyuqm`Q@XKBQI=@Hn8>^CcgLoA>&+^52H40nqZQYK{2>E#_ z)n-&lNAI(8!0PjGJuw3{m7KxByF0y%?u1ah)jWP?XmKcrXY7a*_Mdh(o6B~87r!LR zG93~2*KxA@LOg?tZ}Acw>Kfu3H9Wx{U##7R|L6By;kw4+&u$U%w86ov8wKxNf}8EH z?@~ayP*>RLzUpGhP@T_f?TnJrE$c5gYd!|eZ0o%rTrfVC`RJd%U9#D8x78XztH!4} zR{pE;V=H7TJ(k29qVa7T9PC|5uE55;UwH=$KDBF#R+AiW(5<1Sv_5VA_6^jdc>1T? zcF!R-Q{=3Kp;<>ipQcy3OVZC z^KKmOC80~qM@Y=kzmw3WWR#lbqL|%zy;eur4^=H>a3qqPL6S~e397o9z zim?MTZ@PaGr$&^K6WOWy?zccj^l2S?D*}t-5H}C?iDk6bhKTjFj)`6zF2;Psw*^BtdCt_ozKc-^cmPMd^fU59w%3Ipp+VK6LPb=G5gNt zX7@5z=ujqzuz8z!`FcgUatixTp#$a4H0~Al>xmigCP<7cKK>0!gq4Kx@Sj(FzW zE-BPU%I$<>eD^gio3lUR?+&dpT(rM+f2WU8PWit_#Yv_O0e5~>YE96JVKr#oh4VgO z(AG>wOX%k^ORYS za`GdezPVPA)(u@Di-Z``{5=!N6nmwT?H2E|QDhVlj`XV056!&8&x;X+##68%in2NGN1vW_4m1xh)0*g^cjIAoJWqa`P2Gr=Q#&{R{S z4HKri*q$@@+}=SamDb;W8K6A%T}2(w%PitzqaqGBC?fe{mYeJf3ODbW>3#w@i`)zB z*6v^!3+vqcB+?D#_ROF)#f23|N!S)imhb$yuwfcE2y{6onVZZ)JM{jdxQORROa}kn z)UEnDm@)^^{mZ(QP^CtmWwISIBNitP{yt#)@B>rHA*R3=Q3tK&I77Zc zSkm&8*6^&Q6N=B;j5!g6xE6LjuR1?b`4}T2$+SLo|9rSLl6fXkFa`3VfHgk8gg2)w zaSI#I@Y6DO^$DG+3)EU`Dug18RQ>sgw$2|n3;Ht0atB+bqE~>r6ytp+zNi%DHvT`B zR;kR;>dQTPl+wwb1WHLqGjBb#$R@X<|2z_-e182r6h3@JTeW$sY5-VF&I};*%)T$0 zSRcFnuc~NaTr0{w>7Q4WMHOIJT-O-we+vS_bGdGAJVkT3nE4T~w(c=Zbk+6E&B4x* zffBq}Qx~e4jo?WcA0(y%RWbFHOMKSQg(4LMWQn>0x}GwiCq_+jjkbRJ(2tQ>>FEE} z^de^`u1TOwzAQJce6l4>N9#XSP+mWo=ceTv9r6jtfc?};ZyGi77)>iaJNL+_$n3FJ zN3@**B6cjOkR%kl7D08TONQT0?qlZR9lIwSJisT^`$p?sd6(m=hgFfTrh`BnTZS74 zzhp!N=>eyvx~3LGp^6%JW0$#r2T{=DYGLW0`V0llFRa`sY?3;G?F*cOw$S@@nIURw zgRO{PNu(pp{{3}DkCHVTJwxDWquS|=l8tCJ6;C@-E7nvFNf+o4xiB^w=&xU0M=Jf) zd5D}{pb)uQKcP&g9EKt>j=ZP3njtTMWYqHckGQNk#eW0w!X~ z&+=a&c1juwy%|f64&)eSDy(3h%Tv==33Ka;tM`&+G+lRNu=h2NucDMGuA zKLbQV&thDFbeTrC1)`46m|L<-{dmb(#;4_p2DINmaST*_k!1SkyHDd1LpHjOaO~5M zJ<|dm&1UWheH>uCidEem(8KUXpSqX9aQ@7-;ktRsExAZSA^G&#=XGt-*#^OA?#!K6 zrJ=>V=ZbQlz~Ox7evQ_ef1<7~PBP;$qrE4Y|Dm_ugB$caY@>d6`*Q1_be>?(uumh_ ztDg~NjsE*LEBo+2JGyHFy@NO{Tw9XHG`y=zL>3<5~=cm|JB0LQ+O zkdSn<;%wemTH`_!MksFT-lAbKT)i}OroQ7+W~DzJ!rfd>c`Nc5pUWSTA&^~xHiMts zKkj_E4Z755E`P$8>+MqN-jWYCC%V|Q$B|Eb<=5vzP1j-uaVOh^^?zHl8JP}ctgx4Qx!eb#Bf2ZFb-Dj$SVZCBmP~SX8EVWt;bVv&5;^r;SJB zn9B%hGj)58W$v1YGG9}Vc3LP00L)IOJ7w4{ebZz!?+{w)VV6`40?bnzcSyrT6VJ)(1M9>3)j?9*I zS#9salswQNw^THwuet|s?FBhJ*M$h~B0fcQ zZ|kI{Ny$o&2VERCIF!Cai=98?0B#7B7yU{p88jA-eR)4;L7n&<5|4u*nGeD*fy;Yg^l`yhb;qfslg|jFLWp7? zPoZZ4#DJSSb5p?Bm{a93UBQ*l2C8tN>@z~ijndY|(Pdwp_dEEl zX$5tSJJ`2`XHLeR)xUEIW+W1ichFC}y0li}*njVEaAZ3YQ%hPm`NmGA zcdRK9ty0&W@o;&T^{c7MNlS}<7FNmJ^cQ*6LGIbMvl8?ihFN=JsPpa|=r@vMDpL;_ z+2sC|#rPcyqDbVM^JXfTkz{jD>IV*x|8QJZ>5&Yl8k~A7U;s%^c*yc}N0Q4e*)T^U zEVu;X+RrGgLS+bgVt;?+3OUJd0g2n*Jqw#OAbBFOEM@Dm_&F(8LZ3+NLzoH_k!J>C z27wHC#OX{apmASs0l-DM_Pe|lhH$euE_c227fXh(?z`f?Ct^#JSy=$XFT#Wq$v)p- z6$?N@i1!*wQ6iT5{!z)VoHSBTuLMc!cl#LTfDQaj*VlnVyWZh>$tuz^;{M5i(I>p_3DCg8-Nhs2U%uO02OD>|;es4R*C zfPor3`>l#upZ%xVi^?54NZo!J8NQh&)Hl>ORQyDATkM;H(*M>@!Dal4GUq%k7TYxz z9~x?zezp<2SWRn#)iP5-om8$dZ2>M$+H6q%grHB?Hqf^TlZpfaP%>^S!KI~v zNPd8kVQPz|^!|LuV&nY8iY?9%8B}gkEe+=PWGesDtr$_*zAs(#>uTpN&yh&evSVXg zi41atU!vBPWV_bNI^g)4?4*B4sCi^(Gj;mtuYD1CUhk&vog1@f>b93om-rBIyhK?4 zr2g5=4F6cAa3r5r*r$d;uB?}mNQ4`4ufQN=< zW-8X4b_>4VPnyarB2fp&ur@!!T4dyy0P7ivYzGwupPP8xJQ2EzaarjZ2MDhmn%iKF!0w~Ul51dTJ{Im&Z{?+{*EZ*cj72gU&#wx zmUlc?e9ZDreej^apQa71FGZf@-c3h@bB*N|Bw9ZQqghljB*HAD)@); zf0?k+VDiroiK-CJMsuo^-=|G=p-JelH^445bO;=iKu;#jBMzW_YNLc|uHmW3ZD+_5 zcIE@{uS$uFa|v6qf0A;YeKoLX_r=rMd5$4BmYRC&rfZX&kw z;8CXMmPQl`XeBp0_!er_=8-+qCbUFAhdhoK_cY;QToX~LG57ubu&8qrBGkZtG0rc! z_d{f+xAD^(E_S2*K?@;gvZd!lOVd1LvGRuK7UMo*=blsM>EdMi*WTT%N974FKi>2K z#ek9px?n1xBP0tb4T%RH1ES_$hI=?k>wfqv0>p%csi~@ZcQYZw0<(csaesZD^=ZV- zy;6miK7+814X~!Qqmw?~l+pu2wx1VzQ>u7melH;CEoNBN0X(Gyy|+MBMoMoDH&YB) zpL!*20-y$o^vZLQJD>>HpSwA+`9Y@-gt**ti0YH7w}8g!24dwVK8s%FqdTB0eG^9; z-Hx&x{>gAs+7I0kw8{C(d(R?=j`V#*&to5O>}|KJJWgct#--6W=N+6_7?8RCCOYZ$ zJ=jJmHOWpW0Y64c%?!wskdkW4Y2%^196h%^G>W1_q1rIP5A#|+3S|}sz)T9$Y7(SW zIuXEa5XOLxyloQB7uw5Y5fVa~G!BNiS_A)YIW>dIM85*l?!o^;7fJH*D?<-ku&4gV z7pu3(%lOdHlC<0JDUexi`|KNib;%U*cTx7q6BbpQW*~m2@cx+)l{_k zqE;}#mg0meg90@B4U{7FoZy(@JM|b#@L-K&L->ka53!u9n3>mTe z>!xXu)L_n(=X-p-R&yQMr=ys~jLsy9+vO`!ou_H+tRPn7FB>fxjm5oRbWmHyV8pn~ z$M!p;yc;NFpQMcL?2bgqZig~Hn!09H)tzJ0t07t~X74rI3fY>RV#+w(-?!vZG5vD& zt_NDrQ2;3H(&Qkdq2If@vi+G;vHzR!RlFnLnL;ld&5wi-5r-F2WpifIB$}#H0u%X| zjQ;${gQ987xtsOxxoEC3Dqu{0(RvkR8Wn|B-UX2W3IwacKzd~$y1|iDWUG3=Mz$kaLy+O8u48NRzG^Y_C6Q@!_qaM<3uKPIg(>8Kau zM-u%eDUCF$ELOtMO)p0p$*r<(`Pm%hk5{z+>VbW_8GC_o_$dC)%P@c#5x_)+?Yqj+ z53vWwo?jY5QpWW|i_dj}4KM)r@*T!1m@-$j+x6+`#i{iGeraQ5V`SrCIJT)HB;Z>9 z>xBaaw5`QP_jfYLY5x7MZRY<5qk$iK@$t9|x?(5)>tlS^^_b*9)c+7_|66LuX9e-J zqp>HdWq{C1z_B|c1++T%T|wyYHwB@11=MKn?*#RyX5nb^9^yLkm2_5FAr?2^PW?LR zHwjr)6Qi@}G?=QeCJZ)6@_J_HyI2Do@ibJ1|hGe}zn*P31ZoLX2!ed8%U?GuMcaMT6%QdW#b}DiqR3|qpwSW z&OZiozSfT6kqb?ZFj2Wc6?`^;&W#a@KS{n0dsRRRB4+AaMH1zi>jo$ z7m)O-vvT)`)@ENc>UP1Bh7q=N-v{-Ej*GabCAbrA?L$=d)djL^6>>T>`+mnhG3=B0 zEamwlj90_$4r5IocgpzW9B~1Ni6KkvUdAR!n%@~0zr#23ef@*PGQ8-7{viImha>|# z;gv|+Y|h;*Ed;1|1-!Qfs?yo-sSVRjM&D#ZZrtV?q&A&0EBD>&5Q9xct;UZfZKW}$ zGBR3sMtwiidlRb6>ebOUy9)wHgK3^2J-+yZg?qfe_zX45WO|uvznDuC+n3t!l5=Zk z)#+Q~h7CuqB6|I@N)QP$X{;PrN^VCkqCV{`Xr^%VgR~Bgz`x|2O+&O6#=}-u!X>xugne z?nH17yGa1aXRi3BjZM4h>*}*=!l|#4@;rKDabxkn1xs63NFgx{>&hh?iYZjd2yl(< z@6%9HGH==ABFm8#cNvoF0G?e|`?;etI-3333j9&&xDA+*<%agUC4lXwnDLeyp| zVbN)ROY%9jEFre|YjG-jzoV3u_&Gl&bDgD7(k*c--LL}VF<0|SJfNSULqa|-eg17d zwK~tBFERw+<2{xz#1bIv0=e)qgr?ggB)9AI8+K)*OsGDUj(*z$^77Tp6BC0q3IQpK z$C7eL2S#d8&RtMWc0!bqgF&Gch@$Rw5moQqE4Lq+Q#2XaJ4c{EI|1v5Pyb|C%15er zeaDu%CWKjPuF4w#g?#-5L-jIk>aH`!4HxauDGF%7X*emZISq7h*l@Y*42kR<=do~R zSW4n+T%U`PNWHJ?Otx0lb|@L`F-T%co7V7(rfiJ0*RfK^U+>T*sk4l_;wMgo9+-vz z^r$K7vcEBU-Sb0W0m4&|H2Vw^n?-KFfUn>M0&e&A_T1rE(e01FI4$68-)ZynYahqh zOfoxKeAhP-UH$pR4JE=SeqK3N6aMRp?N6>Cs+hrk>Kz3ViRYgs>T)XRyuI1qI`nGt z-f@D#R#w_O0)oy$SHu32eg|}RQ8{n#Fn`Zlw&}1OJ!?{I8mc#vZh_WD&h3v#J;1i2F!#2!Vg^Nn$;)9LB!z_=~)MCW!6*KDwwybo!`8F7Ws~f)E#a$kr06^1XwRb%mK{qxpO=B&8Ug1 zT)|$Y0tnk58OEC#L7rt)bYz>kTa89JPyvhRM1-UFNLkFACaZ?$c}?W5s~|Go3p7vZ zvsx-%6Y&f5)xOlqW8M)gJz%p!X0ZpdY`xHTiboT{=3&_h(Tap zkjJpj8KO;JXiUq@tj?*vF0UG(bfYunmYb0o$Mjr>cK$mFi%%WwsB9wTlBry69@rQi zQx3(SoQ?fGBo%GZmqSQ-#AFB99c>(SD2O8b(@X#+Jt!+p+_g7+b!+Wp^}rS%yn4{J z7~Vt*qy3BRzYgcqf!BNovV2UmIl`Wgf;~Iljap)!!>NG zyt;t&z+XYe;w@lfR#lk);NOf{RB_Cqcn$dF&`{jH{-?5%&YIAquLi(w^wX;Cn%`i& zZ{_ZjtplRc02$bdu+fncu?ww|zs+3dfjTj|cm2EfpT;zOdM)du4t`&=ozXr{>f5j( zdSK_KhR!?cL@lN-GT*jv9OzVq?oAx{G(juH$97ArYPJIKc;=Uix%~KB)t{_x;fV^r zQf5v1h*=(CV3!#_wt1+r8HbcEb1`u`HSr^4*QET4AP3*pz2v@<$c`inw7eG~1y8^{UFExcCip`~M4jbt^c4gWds zt?2~n2P0ke68L=A0jpGAlUeoTAUR(8;mz)%oZ=6=uebvyRGx~b$$!sDQ$gHi&V(hc zB>BO{Y@>^LOFtkhHp&cmDXGXQ3fRTS4(X%80%Muq8Auk+0N8IgQvA{Sras|zLC;W5 zPl$ZfEz{1MDoQe0-z;XEsxQ|4pgmx|R*lh+t-u zjfY&yS6I0_1=-yj1^*>-;pgeEKg@PoQ>=2m0M}e%R^UN|5T>gm5HPd6Ite|k545+n zc*y1~9I^*O?14^pzyIesIb=Qn#Tj=(Cgu%Y$W3&Y=*(FcK(7kj7)=}A?wj*{84-RD ze!Iuk-zTJ3atSaRDi?xMe&_KMM>p93Xcw1LQXGTEfED&584ZK?g%P}I5eFVNaJawS zr6^HTm_RHt5Fu9&m^pH#|NKTapwX)4SI@An<}`X z9#6#_D>D6Nry^;WFx5#U7y+8^W1z82o&&Lw6-oK~PxmxLqU7(T^h{ETI4Am@XjpxAwgxFS`-OR_e(eDGZe)LGOIe-lKm++_{=qrPAm50% z?&!-KqCEzojKoxFOBZ_nnktV`CUPYb%47)NF?;`OV|79MU@X|}qOIo}K)@w56e|cJAc8fo)h~e)EL0fL|Cz`@f?##ctZXyxKnV1}Wt z>y}(7r*jmikViWV4rAwm^Z8dHl}O01qNoH7pIM)_=VF)yn3|+88_cR9vvYIIZY3)I z^Xgg947LnHl`7Ju8qbQy+!`YmP>QDxHa0@;P9LgiQ&X*&__wV&StLD;@~U_K?g}dk z)1zme*T{H`5kc9BiJ)vk>Jhtww%YdT8ew}27oUs7G>&r~u`w};(e0JGp65_mU8BwF zV-f@bR1#4ZGs~!Uj)V*$`k(oGlOx0d5u|jA+#SL!AC5Xeq;+rMRkI*6z&93g|Kw`z zgYh#pz#aF^wfpT{3f*%lR!0@srdy@WZ%O$Y|uokF~Dpuz{dx zwuFX3N>RzPv612y|4UrIK&wb;C%f_4pLl*NwWZA}mxSD{y1b@YRDkbB@j+YK?c|o= z2=(xO6{WKKD3~*g0j+#JWR2nNsG89nezR4ln7C3H#081qkEw(?Yml1ND`wC@Ft-699ZXq&UGInuABP^;!G)*+SMc}E#&6Bc(V;} z6(A%J(tp=H;WxauL~!^9!iSG+_0r>Rz}#F7i#_XDE)HawMwyBB7e0M{rOrzLh(8y7VtS z_Y#+)jna0i&_n)Mh6G1nqY`9uZ?94j!gJfx_uYkz{g4s68B+HM=(eB;?A9;H)Uywu|&DSS$qsLVIFE6(KzvkQ`tJEFeMCHz&$ zoNH3H^=!0x5+D?xu8+?lbfjt>(n)dyf%k?f4Rzb~@j0ZXTKXIUDXnwbE%)!|685Vb z90A(bkApHa4?&2&-oEE%W`QlVMAtu03P>WII!>p?e@=0vAh>B?TR zGt6%2`_#cZVEc_f({B2GP6G1kig;1oF|^)bjKi@}{SY1z&@HkBuQbsv2iYG6ug@tO zWw+{);Z3CJRjL7*tUM}AsW5nacCIEU#+-tj@dXLrTFGOD`?QfNaN0q`F%WTU(6sXU zZpOO~D-beMC!7ssTgK_Esw=Erfu|xE?N?feUk%S-lot-IWOUlJBTefq|2F73K3JgW zV!riZk{6LRR^){F0|xtN8_oN^H{X zQ650_2AvIbCa+DsqLqjq>@-VR^|HnMk{YkX;`T@)xvcgNa;COf_qtkONQC@T{W;y0 zB7eD}wNd`_!w=WGF^HR-tyYQBF@m510;EQuT2x7<&W1>_6H0yxtB;r`ASg@f9-;;* z-0~;4-kuzXWyxRPG#!ICxJF~XT@?ic&g?_8wsB!2pt(4oVQg)p7xycP``rAjkqX$kXMtvV3t z?(TI#F0$rj@okVIyV-*F_NB^zMW0!|m^lhN?es$VS+z5l#pZ~U#m|6`Wt@92H}6pG z?I*Q;G>Twj*iu39h_$TZ+EzxTRVl*hp2DC;OPD#PQvs^jg|=rX+T;k8xFhsd(wcfi zbWD`uYipqSGXI*xg(>8mTaUIVUZfH_-shxg^+988Kx#&;k9=pPQ>supK3_waS$?H6 zKr2w+aoUm8{7Q38GVxD?&}WLLYMu5+T`F{j--_0u%W@Qi2&Z(v)so(x7rUPYY8V*AIIcK)r$utP33i3_krvW5zet>n&OWI94WP1h zY_2=} z&icBeW57~!T2{jM7wq!v^2g!#_SM>Cy?p;sDPf*;UQ&@^MO&^T974m3FhVJNN#wqi4AQ$ zVZ^twi=8jBEkDY+JVHQ&dSKmwMcZIBw;_aYE#1yzoCMH&N9w+`SL=GUFKb1tmvr~l}*oJQ)g)^(xG&m zY!j7Iay>u8;ZphCTV+H)(oa9saUm#jt2di@<+eiJVg@kF$fOBz;q^Vs`)&mYWo4NE z(!nsJlVW&nlQrNjQ|{LRczHxqBg&awquGeW&rQ%JE(>Lr8ssf_hE1Qq>iO1&d z!2kw2%!^QyxKNSm={FN3u5pfud8d-m*V5ogWj_L@#V~bVGQF zy6nSt5X!(H4JIkcoPs4Vf#qBHV`K!6a(wpSLpw=i6*9m03xtMIfl$wbHTI~_#zECD zhamb;EBCzU)gP|=51rFraH5LO2VP0C>#S0Prg_?@cCoCf5gB4%f&D|^*vxekrQPTd z@k0%5HW71V^`p@*zP_S#IOCZ>coyv7nHG}fQ#VJfrzWYrE75W048eh>#rxwj_wT4o ziMylB?`kMzdVAB7QA^41p7EKpIns#p3D?Y}%`uWXu}@ahD-XQA&`%@aw#%@$be*tC zUgSepG?!_E`lJfVb@r=+GX+RN43O(8Bt3b4d)WtY;FzZWrG&55d{RCbWn7?|+w&+AFm-5bZ--_x?+b$BZMHvr|Y}7oC|FPc<(; z98Es)d;da44Ny&-pPJmXt?;{LiR=L}iwg0KW-hUVt0+%9KuS?`ye@0D?AUCon<9N4AVEe{o^Vgw;Y z_*23;DeiA58x8OWWUYXqbezQJZ!f>*bf{sgc}7zvORj ztfi_nNF0ZCUPx{Y<$&_mOHk>%DU!+tGTZuS7fyEiUodG~pc5IDg~sBtXr;f6dSW+B z0tgHEEJ)$WZ?FqZ@Zi?GAE04LPaJbZYtv|H(?3#Y0eRp}xwbXRkT^8jsGS{zU?Bsg z>-?jx4yyAaAqXTI^O=r#Ntxu0!^|RO@ZVs3r8^S6%WU?36sEQT?WP$o;#h+gV9TV? zCNp2=DN|F?hA%j&B7<5h48O$5&xB^RpQ|&?ra4pC(UXpE@Xma+>pOw=q3EBY*mzwy zrF0igbh;&N4|6I_H64eGJf42V1_`iM}pw5xH@QbCM;nbl2mab9AP6+Yp7ucb~*1i^~T@#oKFwN@2 z8~HEdeNWXd+U~E3`%|7^xo$CQkrh0L)7~4GA57I&PrG+h_mA+R8)@lIuI&RCkG$7z z%}kl-$J<4N*aNSZ`Lkkp7bDfym7`pK%YwpL$hy9ZJ*6ra`U>xn42BbmLF0bX`Gq#BdpUeY=FAoQg)=1YE} zgU*+RQFlRX??nQwqiCMp%||NvBO>C`R5Ulzx9&5_$o41zx!hi5sMZ_=w~yQRUO_&Q zlE_vh8!|l+7n6Gr5szhWaRS^TIC%~`0#=H*RI-WRFOw4yqoz~rdno0gfj71&|o1#1Dp#W zB=qeETk??KWHTTds&0?Z z9b9mE{UN-QJjb~B4dvRs#Gm>CxuFil58?V4{-|jXan*~Zd93JWbIx4RzL{T#eeO5K zfiG;LRE>J`r=$z!kX@hh;x7?wwVX?c<%}{^9swZ%bQhYyl@!=MywGU=(sSqh(57VW z#iA~4J%gahQ(|__5%^s25rgQ-8gEh?#jcU5p@4D>yZgL#-VtQy4j3^1^}cdxr7=cK zUs;fkKS3OeZ%^oDk+RlK98pTU9vd6G_^9DiUS4*dp7unX^Ras@@Xs!e&;!|cT@O^6 zCF@_4<7}lJ-LmdZp0|yg%m($H9M8-&&Nr8Nff=WD^-7&hCuRNZC*OZeJq92Qz9%kv z*|zVze$e{(+)mmC<{T0<&kKM*R+ug#;iGyLrT+{bk7g|aTXA0o6Y2IP&&!Q|=OnV# zO0Qqx46Kbs7@`NW%8^D1Xub#PH--5pWh%?`3iDT>J6smtRV{)E~JHl<|B;xPxm!(V{nn|5CyAM4+w(Z-IKINWS{b zFEu`k$`KDXGqjCIq^jr&iNu?%<|hqjVa>_LHl%KIgFnD97dJ3xfe&rWWS{lmUMxKi zF`#AauU!BUDECS?a9^E_c{Ao(9H1|XOyLdRK`mmh3XqBWB^T{J^L@SnP8ll#7m7z| z=|ryV{oczlGSGz_z|BuPqN9{Zm=fpxSn7V_cLYyBOvrz)&IO9gvjrW_uPK&eco6%w zH3MfiE>VbW#9pCX8G<_2^_^FD{b1Mq`*~*WidE2cLdNc5rcHu(PyWT0og*;^IOCT%Odjs(t1y{48aZY+Dn|2jjLb57OZ z#rz$kjR^dmNgUJAv*|jxyPU48Eek%# z!=989Ogl>?3?`-=Tw?I*mjfcYsXvo9=E=@bPXxX%sZ*Qn+uEwO6Qk)8EqYs|Go(}- z#%QTSG0dS+j#9Cb$569tjvid1=t)s86kjzz3gPbCX4g?&=F*{Q)Vhql;Lkb>N%#~C@qP>sg}n8U%h{@H4y;v^l+BNk(zOVbg33|3y`dYx@=l#ph2<^4wwGZyyKI=HzPvYp`Sss`N$Hy(7PD*%E*#3L zaQp14PlN#RODFzEv3I=o>DO?X__P40>+AiegDp{yW5Wjjd+NnfpLY^}O!qw>xIQ1J zk5(hX&54yOt^}LNWgQM&^&fscR>&Z7{cn|gaJ#EjuKm6ohYW7`E+F70FX{N27uz9s zx^IR~p#(mn%?;Mv22umt3nd%`OQ3)CWsZNdC4*o5F%5(ymsN_|#*q4H_%=L)BOjDn zrd2Z}lud?JCyOpvnU-Lg0GTr^W55h%)?Qt)XlhcJmi^XV@mzY;mpi3 z?}&Un4JPEYoQ=45N65sS>ooYo?ZS^YO?RneTDTecgl74Pht(=*(TkwY>mW~VNn{7c zeOH;fG>gUvm)O@5n9nyV=-t7Z<_kX) zAx=Mga`9+zwCc--ySm31R?YRTuGZcaLNxlSsH_MMmyCHTP}@?G1D1pcmK;TqK(r<} zmo)D!pXR&iT8PEHHZkIxPwnzQI|u9>GxWb`=^5&dW4`Ta?0p>2WQBM)@MT}tB9_%( znez7}XkBlE*A{jxt+aUb;gXf?&R8>~9fxrJmd`{4u|D5;{Gu+!whO%+l{G!H--dKW zv7m1q2VVEW5k3F#biW=q#F$sHxv&1IL6I)f$yS1>G)4}S9IxYT1nZPw(=?sHVF(^g zS9){F_p^j@pY2JrJIzGq+9pb+Oa1b%R$?Gn`l};d8I+0D?od{RZ-H|O>gj4x@}ejl zW_sSpu#j_2oPJq~_?C@Nvwt6Yd^vG-BhewR77%;&;NmCO$Llz(+8R#lHhRCH6yO+K zbNE~6omA`EaUHAXrBM36`RYQ2Oy_V7D8zF0Fd!u5*RPU~Ek|Q^eToDGhPQ`4!$xDW zhBqSe0XKGmD^5ua5Crr{_*ew49ngO9qK~W2EQJjb!PrDe0Zl0SQuM@qRUgfw@f4<7 zL)$yWkWlwbhu)od!RFR|MvJz|U76>*M~n7BEt5-#%DxR$9Ps>ga_4dkZ^#HjCU52cH% z!12H9rp*Kya zjjvJF$CzrwfrtJxGEzela;jR{N=!HAbAoDh8B*uIhw>B}176aSg}atK>kNi~T}6>XYdkAw5PDoRmRH2Vbtm8IR6@$y|mmTM^r?=8M!xnVh?&aUOW|(M~ zFEb;@sh_p_?#c4nh&vkTXW9*_azbIF9z&CJ46!T+FJqPKV4egw2;VS|;k(UiX_CC8 zrzO8*>44cMbwB7!^f8$rrO?kXX^|Dc`_NuZl&cNg2He~dlu^z*Or4F^DIzYlty9&w zb%k#Y?txM?9)l%JJoFQr>1@HQY4=3YPgPWB7cC%B;re|RMzBXe-j9|vs4eT>nqDk5 z4E_kEO``kb4t+(!$7_aK1QKL!(#&l0<0=C3)0cb?V2Axx0E-<4_eXF?HeMU#*yZRF z*ZgLW>rpoeKmCQ0q#M2#DY)zjD0z?kOAqNng1U=f*2tg(7RGR)5_mvuzjaPO~O#fY=wmbjpFwI?j zP{Sf5&#mU%N_yIH>PACqf_^%9GC)0+xsgl&#I12z%vuW`Is_!vCY+Hwv*!+3?UNJ* zLA+T2j;9FmM6sc_A!unIc3(JRxg53L?)pJbDA`21LgGaoX~*udLkY?7bAnDRA@ZWF z!EB|>45tagy?pg{@6(+|o`D2;f4r~#hicXimn?W-M<3zY?^R(J4}ZIid!#OK!9ehW z#(W$D+RXF?hp>RD*YEA!TBMrKY}QDP@=KPIgSE~uMqAkg)n z=+BAp%BstTU_*b0HF1yepw2xf`YOP+QJ@G`J#HWNC4OJTbK+9}%x>Ln-EGwAKZYuF zhB(ykCGhJ0uGAK3lHZN;jQ2Y~%67i7G#_A zpq@o8;E!p^wU5RsDdXw9(v*);j2k8$p@kkp*46NvSPk(uPS{(E6Y!PQ(zSkRZZ*FQ z*Kr0{jSMoK6LO#2kQ-Kg>diNBm#~yrJVK5|RsQNJPQKfdert6s&RG)K(N*@s8OPdMhlQ)ds&7^-pqg`QZ^G9A( z(n?6?-rD-$psn}zZo^>Kc~92l%F3GAm02M7(C%SjLoooj3}}4;@oLDPq3&?o*yEip zH*w>uBn`k9DGza6{XVt|Ft2L89yOv%w4CKtFK$HrSe3CRNEl%0>vvOsNg}b!kCZCy zNb5On)^6cOc+0Ao))Uc!Pk}uE*)BJ}KofEO3Zl0>iMmu1@;>Y=@aZH)y5eiqH*X5% zb{`7Lp=u;eBP4bE=5d9gM+$cJ{-#+4?3HlNEp=W62yz+`WKLnv&28f(ZL@3bnMOdW zPD=iuAtSEA?I!AJ8L1sxN76#LA-WJ*M6_Tf?eZ9zpa5HzdyK52Qhp^@$oi-0=j?#1 z?e9+YCa_nLe@O^&H?IGw*l&jK#aN!W6|Kfh^4M2sLG!&rx*I%1tLcPS5>@y>2@9+)5+Z&dx3!5Xv-P zZe1ou?Rx|Q?8-Sm3VWV)IQ;zU-eGk0*-1K5jug%*>l?<8Ea$=9qMb?_z^qWB| z&znk8%R$LNzq=3A8MPaJyrLM?-hOY?L;6vSiVXGp^%J-dXVNuf27*5F#1Pa|h}fFO zcXE4|v>iVq2UX$6VGr!>HIj-+>YorYLjdJ<#&ss#u6cX*v6@kN4)zi5wRR9a1aU3s z36NI<0Hq{;Tg(qLN4urFVID_MFeKMgeB_QmYM{4*DJtuA%CvdSbjA{nS*YI3>jh)| z_M=>_{=WbFjD)YwDJC8bJe12>-Pz~eu$DLT(Y+k1vg9JS=i=g8xT!lu?7}4D(fW^R z7)l%azArym0z9>l6_?&qSIQNp8Gd@vcq(5wh9vFQRb9df-KOt$9h6fkzS zln%XIOP{W~qdVMjTE;LG43*K;nFMZC5z47Qvz#nDN6kUx#Cfef>Pd#_0S}f!&kOtR zZs4DJ4<}jc;z278r}KJ9*D!~mCW@RlbmQM|Q<+)D8DpJ0B8%2feidz7?ek5IRg)0j zFq00l&kU+B>Jhi{+7L@D(3~%Rm5TqAAMG6WZJi1PzUhj-tT$=+`g%3NWFRk6kJ6kZ zitc057Rd88$%07X6_fT&S_)X?zcv z2qvkpl4(Cu6|+be6=Y^$ zSWlW_d6KDpl-2R%=lc92_V0m< zZ=YVT^oqaq#xZFC75cwefZ>LJV&3yQer30u#i<@~w&uLM&}cl=A;NxWrLnFM9hMGt zl^ebg+UW9=@5gnuviENzrB8j9)qz){j}aXy(+%GKw={w6Rfc+;)yhI2Y;0;Hi}!fW zN>?;5at>BQHR*<#r&>U7gNnI70Oj4ra7pBxaO_OGgYkBfO z4Nc@lmhSLyz!*B?F$(K!#K}1UE9(8GODLN4nPSIMU=x(>mXiw28Hyfv~|7 zOs%D|uX?XV5g8{N8yj6~hInCCX6CP^Ql?c<2GWH!(B(s?f9SpQofHwdj=Ubl$MOnm z19pAd;$8-%>Z2EbdLq{5PD`TQF!z>3hOM$bG1`R9d8i6ejfYW4s94R>*iNYXpT@4XsOK+t>4A z@*7?whlclKvEu8vs0;sr13 zL%)M0=+N>5?swG*;S;&3EdYl2w5}j7EiGlpn_h3-Vl#Ll+CWhPk$5H!;IgeDeW&8D z?4V9tZyrO=O;VxV^_VxfE1XFJ{DFX$`6^WK2$)P($g*X`IUdS+hidxN@sEU%JM8~@s_2%tAa1eIP zVVUb*oAA;lR2Q=Bmb(W*KiBQ%0~3I)ZCFyy3pRDar+IC_=scBjc+aVoWPr>corK97P!1^60kHpy~gCZ|3V=_;DTP$HFuwv#M z`=wo@ebMYq zz~v}K2w?ZEppt$bo9XxQhY?4w8p!%dK0bg}zFxxbJfBVZhS#F<@)rP9cA`p=W#lG{ z32e1{dBk;3w3j{g=sPJu*kXcqHc{j}{ORx`pJtp54EW~erB3u6Mt8x)aapkD76_^Q zpGvdo+6d|>KL$eJ6D`Wphm|(L>nXDd+U~H+y6&Lz1*t@Bv7v@ZGd~M3hwl9EWzRCE zJGAK6Hx~5FxA~m~?A{ad`zy(=UtAanlIkDkAfgQg8NEudb&QBZigTw3nEKt8(AqhL zUF&tm`eW9g>q%03_9ANSdqQTPg0f_mG*v&u@A@0kR`Mpd`g=6lFE-@Qb!<6Jf+#Qd zDW*ZaH}f9jK{qX$q*_F&)9MW8m4qK5qv6UtNT=LCvhp#j8(*(vj*6~jT<6mT|52O& zofQN6Wt>p}IenjR9sf;d{y(yF3nyqy?mEN}d~UZEl4ROWHp;E`dnFuDIe6B>tpG8_ z6O85ON5|9jsWDA`vek9QgzMU_<k32@fTdO{X~>8&_;Lg1oDXLQ^M*$acyQxzpS;=y1)#xW&7zHkNpO(^f6O zXmcL%uolh7Dedc5d<>PMT6%~TT%0Wo?cDrYIe0A1bxj&v4ky{ID+kk8Lgz4{S z-<576BT#|~5HCDDm8$#R@*S|Zr$tFdkV~+~rhBtlV0JMfPEQJ_rv`*xueFV?VOpT^ znG^|5*KE+>DTZwLAHfCw`T4@=z4d$YmA^*xP{8l$ z1kbK5-lHIy>LbHrf7W~ORcU*lFaS-K)Gtm-1BaoaeZHDW+At4D@; zUD5@jwTc5dXQvFzfbQ=5yotqOwtzckN%*v8G$DEj6R6u!GUhooxv}RIkH!#8wc*ny zsko;sr|SX(c-k_g2mUW*+vVQDT|j#EW&C2n&do~FVgoRBg}=`zx`EY6lH&!ze>N@Y zQ2FwU%EyS?IVVEE=*6RrG(em1dTBi!Hw)utT)-a5UO5tvLOG_ko=|f?TmF; zF+S7xZPH5d#A^y2JYw2N??Yj|&gCQR{=$kPCzYt>vc~=kjo2XC_n&Kb+{0aI@OXVo12kCEsj71aTK0Yy2P#M}9|VMOPl( zS@rX z$*H=T^>Id;A$z5}q#!c#X1P*)Rw{Z1{Q52_?Foov?PCpbGz22Qbjcw(2j4FX=keHU zEkE0eRGhBS9TjC9{)7Ax80qjhP2<*sC$RbQL<=ayDPj9cxxLaEK)mBl%-))pez{y@ z<)nJro_EjMrGF%CdgwF0cii23paZ<4z$EzE%R!-S$*BYH&=r8U(z6WJf137w*`GC6 z!CTm5ed9glmg~gEYS$;)IlDm}r6*+fWR^-28W^6I@)dp2EaJT_R2wlyKL==U!z_B~ z0^M%V)_)ZD`ks@=4;jYhG!0z7%k3jxqw> zzcA|65!c50+w#~`kxW%v3n9ooTT z=<@&dD3{B_VLXWa;=QXcZy)X0h*L<8rps|H`z|<>D+&TW;ZwO!?SI?HYTvCYdUO4p z7}Xij8pTf3yLEcCXnR(l+Fo9?jnArnU+?dNITf9uJI@XcB9J&HseXhUYR*~tUgJm&W}M*BF`RNgLDIF`mUm<0-B(ltR^ zP(~ITBfRcsqTy|peSVtliM4?vx6mnWUo}>FjV13}lgAb@OvPTnq7LjKORNb~=4y{3yDva=HH3)8K&%cz`3HRD~{W=Kk z8yd8&1KGi&HA9&}6)Gfe{AX18f~-iQp3rjkgTQM7I9<`O+KZU)l(OpQN~9PFg|GlL zbfb(1TTc}n0_6^D6T2VZF|K9%$`gRl0B$ewEF<5}evT6lr%{3Pv!mr?Tp!t*H5hFu zd3tXS#%=K;_N#Y)v<2?QRCPyHDUdhSd9UR;wZ1za%^_XBsl-Rfz2D2On8A)NMQ2+7 z{A6Lw;7rBaOXdw2UhJhe-p%glXR6s#7 z!@dq<|F;SMAI*{69`OUfP2>Ia%d!7iO#U(K<-Y#&_~OS+ku*2J3WhouPPrTkhRPZ0 z>e1Uz+w}-A>vqz_hmS-vy(ANotW0n~k*=52h|rc%Vc_I+6=hKx=a-0f;ytPooB8u%hb0b&5|93DT6)%EQO_=)lqn*8u@6<-4$20`hVh2Z zKgNt)47R_4tN_1YBD}|?=fsy*fV*2i3EdSQ4)bfbTrHMn164K5>ZWw9jCNx-S|FXJ z3!=`X{eAql=SSg)=R5mmwilHtdhKRcxh%O>Q#-0z zQo3Yr^!_M??aGqd7CZ09zhv=k037?|yZrShV_7mTIerJ7L{|3p#s}_=XIb{?_w7UL zR!K!e92m;6f~1t#MvoCdmRv!H25ro%DDp;#ia6)X+UHeFl536Nm^z9B$Cn-$m=f$a z3MJ%kvsS5{LD)1WIB$<)p0fLE7ro*4lVVLQf}<2ZEo}dHq-i@{5@`GLjvLsL{!!)P zr=6~j%FPf!XiyNEFenIJA52d`NbESk?4_qZ4w&&6rz0r2{c*4HM<;2J(Jl_96Cv7M9dTpx4;dBo1L`F0YpM*ylpz*OM0=*7V_ zQ~Pd>SW5`Sl_Eu{B0h5e)3&A0!_r5qe8aRLweSg;Ge|1Y$1 zK%&SAJm8`|SDQ7LKJy%Es=+1I;4+{kTC+r9Xa*fVTTNIABAMR_JY^9=`T`h9Fix&h zIazbV#y#t24h{j?H$b!tv4eyFW<)wLGqd34(W!yPD#)Ysk3yZb^TQG=+F%6F^~y}W zX?Z214Fig>keBoCT!%mP2R5>ZRYW0dosBnAxvw{eo~ynwzXE744GB4;rO5)Pht=zT z-c9{6Ihx|3d~MM4=2G-iSzYGN?YQ+iHcxL2kueA+77e^o z5TACNlCAUmaGz({+<*&gCJr%~CE8l<&!RL^=r|pnw{moxIt~4ju9E-R!3m_p)X)*=8^5IJ}i4K z>D}ud%X(9;BnpJ6={uICMc#8Bmd#9HKtI#tJ_w@d`t{z)R#nW>=bo9XcTG;G!hMdf zNFCtP0|Sir&e#W}=;@b5YQ$y5$%k&{Pb;^dQ`TFS-f@~9uLpGuB`!od(Z7i0n)z74 zV@=EqYnmN5GBIN?Oa5Z#n`s%~99ZIjFb|^NdbbvK)4S!XDjMV)?z6t^2t#8I7V zo$V!${I_Xh*)ayz=bzHQ}zEYtVKNYS5#F7eW^cb`mmVI;RimZ-S8x-QYu9&5={7s6Uqer-zXka3j z2)TLYH;T_FTC6d-2+>kho&*L;#TfgZvm_(u=mn6`cFCbcQ^Ea9&{NDO-B{faAr&LI zpt~F}#9W!*>b=gfK@acDojUKXn^{<@+mt`79U+{qT;kvhaNYJbm@y=36`OHqncuLm z4JBOO(=jpFF90dj|CW(#DC}U)$_lzvGWtN{;&UyH<-vMgY=_M=S6lkGX=Prg$Q!VG zuL|#%)X|(1p+ME{uT8!L%~e9(A0)PGdbaysWVrtB?fDf#s;^$bKqn-M)S0FeJpgd( z>yG<_{5Rfn@Z)0q@=G<1bS{$y5(Nj<>VKai{svr^+O?QF;E_TIb)gvA2<{EP$^ zYNHpLI64@^;G(*o+fBF4i~8A-pmf2C{QM#gX+7izv>iPWxyHPnsD<}P?3}V=88@^~ zsn1^dO>~IL(=9#R*_K!J{WDO=+!)4~&~|?5YDQ`HBAv5-Cjb~!PQgpn7{csjr3@3Y z?XsYVe1bVc7e3D;tmk1<6vBZ%wNDDa8~Q+KIPwf^juR}RsjHxH_2=Mm$1fgesZXyM z;LNXwb0F+cPW#Emy#Z?W?f9c4Y?ahH5v20&0soduX}4u|AG9N*?Z{d3m-mm0R-WXy z#zk2Xq9;2$ksHCE&6Ts)#Z*q!_dK;f$H+=pimp>&I#+$tVm9r1^=FV_)k$*ihRv@> z>g}ZV#N3#}P0q&TyReQ8!O1;2WZEav)q3(dAtc9pPF?SJIW9i{&eBVJs_rQN9?c;t zNjX*N9m3PNSrurhz^4&}1i7S3RObu;LV}8HLP{1JT$8J%UWA5mA`{iHpH`<=Ku0oG za2>~Wajg*$s9Vu@d>MS@ch+}sY!H1rFMXo`^c(7NZ#ln-?NgQG;Lx7uU-^32@7I4A zd)(QXBq}MteyPwdKSjKH`plGL^|Z5K5C4y=FuxX()P7N9XEvI}v41s?M0USg>e?;v zW_mC}uuVOhRn{OMf)t-7P)xPZb0+^hhxvw9D%mJLirZ$z#AyVJcZX3hgLUTWcio;Y z(~gn}2hT0qM&?^{M;g;i(=#I}@&{K{GgcxN#{WxA%XM z^&U=5wQbk;PC@|bO7D1iDZPpGDyS$(mEICSKtxlk7!Saa%F+u&su?jUKJpjR3_(3UnrS&G^R z^iv63UB<$YmYU`9d9St$o#WL;I~5>%Y8i|zPT~=T9hZ0By!ksF?@7k6b{conbQHdJ z?gUv!;X{iI%FG1j1Lq?uZD60Sjxkg4u~4MH|1eV(E`-pABAlSVBspefrfk)eFKsx9 znYHA-E8~A|&S4+1)Up@Nse~-QuFNue^?~+q)-RdZB+6D|9UJWv(2o*|tD?+fh zVBgg3@Kj*|{N?juVO_f8%5zH1#s~cPJ8Q~lC>z}@8{MqU73&4@yLT&)jZslTT22ie zqdQ_cOrxv%kuRnGXz*HfvXm!K(FKl|2t_^Dis}60hl+$y@}okJxrHiTsJ!gRPiov} z=MXz}VZq{n1IEAY$W<4`VCOxAL$9=&Z{4+UgW!t1^H;_rHsM1Fpmeepozb!}aZ(oD zAVSd~UUO?Tf9x%(Fgd8rK#CoqtFAyduzpwgTSj`iO1df=kqpHw*BPfUivr@9gX(9S ziAgm~pi_e3Hm2q+z3i#83Mfo*4j?7<3WW2Lv06@ZqO!*)Tmz2cTzmf@3^RU8oV0tD zwN|Jq7D73EIW(Y&ymuD(1;n7c6YnDo!*xMP``o8q@ZF9yY<7mTq`|)@--tzRe9y1; zj~XcQ`Kt9F3lL&nYmCGx@<%)-{f+`R*}hy2w@Gy2xy|sAN|E9J?1lelP!8n_+Wx2o z-6a_VE|GK7=f_J2^V_Sg$AgjU)jHqh%sMU>Nnm&8l_(NpMmhU@Ia6I3%qcE$f5dQr zM^=MfUM&uyL1!Ox@qiEXz{bFw$s(m9>boH+ww+W7TSfMI91KuOcvsVmx9!kqfh>V* zqKW0hGN%yS9c5?i=%e4Z2#b8Rs+$sV z5kR|vA@#bGA=CX_b>IR#3)>Bi zoliW)Mp0Ge*j5e62Afdr7AJ@}ASNrt6r{n_WWBrN5*SfRx07s19+XBjeqjFK^z;R8 z?6CcCPWCC0+1<{@M(A)Zw55%-tz6ciQhHRbR&FIz^r^?|uStILhcjk!rN{{aNBr6t zD8nZdZR2oHj}Jtvj}&BNWMW@gTqNm$=r#-aq@-q$od-Sdliv7C#@l{X7=XhM;2EBr^^y`s6?w?AHZncmulM&7(#=pj&NpWF@IgzmLtq z?b!;!)z@EOXTl}nQ)(T?0|aPr(VB;jVFgki=mJLp3&j+al-tJ49DtY*%F}=AS&4Cj zeKN7Czghw*X}J|v>R*I!k7e4h{rBWoN3{qHWG5PZt}4l#pkzjaf z#zY77(#!xBNHej6iJ7l_)vlqFdeaScon>Kyxj2@_c>Y1p zs1wzmv_1v-h<~<2&E~4EGzFG@-*j{E9XPeK$n@*H8oAlUX^``Y)>{HTa$OFvXZxoc z42YMZHU*u0`tpZ)BskfzDt=}AdtzZKr# z-{HxRzMs$5{#Gm7k-ZCdg~;EO3h#WBS6x~SJqtu%&K1u!tUf_RnucjdUhajc50Hj0 zMn=;VxBdRtMNxYbyr4z1z%Sf+f#SV;ac&Y01t6IX@rU9Z&0 zohpi8f2es*!{IP$(e6M+r%@n|Ro9R<9NWN`b=y*Hm;kucBFwL%x$3mmd^jbGpVUHH zWgPvNs4w|Z)rqwK%L4q1x!pW7VZ}Qf{E7Bj31XdyqBm`2=?;a@({}rZ70yZ4(5Jmn z=_qLVTqh%M3p;wvf<-wfmW&xurIbj5yLYU=_jkm_nTk%8Ie+>k?9F<9FmMPHrsYns zCzj`-h$70*?k;o~l}14kpsw~`;VTLF$l}zu3Xx(hrOoj=%w!3|Pm}LLH=-`5?nBN{ z#CWS9tuYP``CHFaM7dXuenApIU$ePKJv=?r_V#Lg&!&7p9k2Fhh}CIXO7n(#ahmdM z0{tD<$KFdPvg15SlYS$PAzPb6^bl7ETAcRV%~w>oW3t;F0jxmMyGtRie5lKIk0v6rK007VT%PGp0AKfoEtb zL)1{tO^-##(yxfIjR|Q%6OAB+99~REhMWV~3e4#E99}kp(LGy~1@oibN||;)w!Lnq z97j)Wlh%Q-RF|~&hs>i9l+;uJB?axp!NjL7{m17+>or+r=WP;e63FQW-Cr&hji5^0 zk6*j0a?9O$Y6S-}(p;$<8GVMlUggysCG8mIzS}voi9RnBJb|VmRlRTt4N0Qc{x8yd zOi{-j#a^F&U4flXt_MFD+_O02>cugAmKy#jXs)HoSW(}}>1kM^+y(eSVOg@`Ci);a zIkIo2t@*~TJi*EO$dT8H^bL9_9WW*oMIYrv>#@=(u$#WP@(GLTIL_}RfBn~IY(4_- zGXAZPbdk3+nm2byNL~t&JXJnbCVa>?Af5j^Z$LU<(GJV|;R+CFUfM+MKB~~@ZyWsk zuzLT$oRrTnq!hSVQtSj|Z^cm!W<+j@8h44Oa?4kx51LD4d|PK;`K_%6lZf06sI(l+ za9VYZEyggjWkWv$YBie0Y9jtI)3;m~DHB2PXcezlDEAlea~_2z>EDKxGyy;uyM#I&eUj!ayb>4gYlW&Hj;aL$jjjKVp7y@xqj=BfuAS8Ub z+G<%IMCPeZu$UlKlVf-joJo(}&|(u2&#I?e#=n4mR6cO#-oTpm^T{HhKve3iyJI^&cDIhVUFFjBA>vaB;Y;^+Q?ePnAaWzS=@yU7`Ee zOr^;0D-T$XwCx8Hg2dY??m2%4x%xUxCx_SH6-ZzNvlQGa(F46)^67Lb_X5t_MiQV& z9vS2~c7N|EZA&%BD|)I^;+qH$C~pHI5I|vKCL$2;#IjS;ZUeJd?D}qWwj4+-+KD1W z*D7VhJqUET@uk=%EIbt}gfJat@2O7f&|4WKsU$(~$VPIrR3V!y{L|-px_;D&v=X7E ze)7=g(6SqincM}%a_Agx#RssuHHZ5Fzp4f+!*1Qu#l_}kqKB0u9Rugs-qzopJ^6Sa z`bWE*YD;NZtRF@D@26MFKK2sewb-J-WknzBk_YvvE7sty7>npoP+aQl3uXDIe!1AbIZ5s_ihlyJ@oBH+84c)z^h zFK$|lY;)s`WygWGuQT^vkHS5!8};5;dUu?%be#}mVUbC)|0@Pp!!k*~OCr?5R@Wsh zKxd}H2w2$qia~fN>3pSxbRi;Pa`7ea)D*vL*Ba1l(-~1TBq^5ud>ptqBjif3OSZ9c zeBZrpQkZ{64|T`w(XEIsyqu}V^-x$*98oAeu#S?|fLRyQVCp}$n5~=kNTm!2JYo_) zh>K>za%tdRv+fF`AWxU4+SF!Z_T}LcSPJYLZz;9B`+Bn?NM?b1>$EQ^z3>0hpK+8$ zrPYC|qEur`#sie>__5<#^^YZSZIl&ixj^QOz4CetSAC5EAZ|!~AC3RkYyQ#UY&( zr}*%JCqZ!_iON;5`S;13*u(Fne9ay6sltv%_GFVHMMATWF=n|WW3UB&84IA(utL#J z^lw@3oEzkMdAVMt6@hPdj_+Wi4jdSVB{de>az}{ke_ub(B5roV26iU*&!wuV)H;Y! zjG~CFQyuH;?;;x+zwWJQ^xjyy3QKybwjA{LIQ2D~(NAsYFeXfWh!|yXNyhq(hUK3z zTWdsC-lJa#yKKSFcN*%dogWJhEE%ZWJQ7{mS)m1c$`2F^Y=8UUGT@?qXwrPtWleb( z16$2opqfBYB3U1RBf&uvpE^%`uZ_`)fsT+20hQJjDV0qhJj&p7WK()@`64^wdAWJH z*Vk290W>ZrS}yDvh_s-njx6bOojsB^TT&yhS`t7Z1snM3)`)inrVVX8(KS1RQr1SegTPYTZWG+d;h#$_{9<>H8_E!XzpU+{vOGP3^6g z7sKVSM$HCuv$0=VWzffZ@NqC76CH*t=pXm|xXIoD7x_H@cAJx+`$)F5)izvPUowAV z?FSC;MCqv6Fra(F2*fh)+zr*yV0xG+0% zx9#_FvFqNCUUpc>ce(FoPs`?O(ryKu>8pSmq~o@@`5?r8WdeJjpuw~9)Hdw%gRjKW zt9rQ%^aY0L?=xEJg~HO<9gXQ7FWseRmdVi&69PyB@<7Dyg!j~bvey5y0KvMZRb*3H zV)Q8R&_5%M%2~JX(Fu(#8eY5Lr2(%%f}(_?is*jby*lvaHRGiJgCjSF+08r;BF`?{ z5q_GblbqXGdC~jjqlYNd0g+rCYA*dA+2Cil5E;?*$CIwNfM)UatDsl8W-hdu?`_JX zHYBqEJl zqaz^SJ#TX3=*<#Z1MBK7E|G60nE<6sTT-o^V|W!JwC||)zRVnte7yQEFgT>;QDr}i z_Kpg|CvnlbEo$M(vm%7$mPJrD{vVbNvpVYD4WE^Xvi(;}Qk1QH<42jgY*As6N6T~kxvYRE z%>uh!*m2ygX9uH#lj^Z5>OG@*h_{YUmR2$%*CnUY$tUFUm5p)TvOc9JCsf)4>oSa~ zr=zMS5@EZ=cPa7sPYqU*)+<65jt~F&hgn211Za9nlD`$00Ew(v)`+LyfYOlSRV<^*niLrx@IecH%zE39=*Vr(zi4 zH>+%}Uu0n%7_Gfec%|On&YlmBxSzoEjEICw5XN2ONb(6_Z|LhDuIK@=Tc!87fZ=AV zW-)f4(UhQ6a59lkxh-tXD49B*pH?f^=qb8Jwp^*&(C~W5$wTAa3{(sX12?5)ksB$&8?dK1;vAgdr8P zJ-!+A@;qnqP#h0q{=;1zZT-rsr(K^!;GosB6Oq zitlfB+y%M;xf&qA!xHzE^@|+bDTNB%1-95wzo6s*y#Pe9gD5gL6I&V|^37>6-yNa* zzpe5ms;^MD+1K!N779?X>;Z5QAjhP!${^mAi45+;KFAEI6*?5*kaf z__pj@?w1WBj1OaI>SRoEDUIFDObaZQjbR)XCFk;pm#h*BA3GIc*3%oo@H?*NKr3sk z#w<`sWB|JZF7zY zu4+3OaVrYdU`h_4U^``gADuUb^u$dD#?NCKCfqP+H({Zt&|r<6~p5HJ09!QbW4_2$$^|-NlNU zOU$HadZ4%mn<;EetW#sG1wTtfJk~iC^72?~ZOsoe)w9r8;FBA}YFG#H&(ZCATs~Ga z$#QYMsFjKih1h!}`~UIPUT;-2rgYXG?110)kNtLK#KqO2%%;Wn?yeoWz08mEE8i1L z4jbGwR56m!81RkAVIZ9zzZ6&7DQ@!2Ke(}x!iyEc=DDDPIGK`Lo4JCOdpX3Lq)d1K zgKTTb{#si4!C-yQx?$cCIjF$HigN*Jh@EhFs{>)6=0Cz4wkKUn<|K*@&y!g{h6PI! z#m4HlZ^DG@%?Z#uIu1ywEt;$sP$R+Sf~7>E2LU&v7SfAU{pfXm`!D!5q?zFjAu?1w z;1vC7-Q-kmmw8d{oahmag^%dyIRHFJ!*z4_!0PX2A{h-3nlNFb|J8)+ZEC|i8T+RV zXA$D_jHHkS$5y^05Oi03a`xEm|4%%mTy1i^v8!za%-0BJ&|ex-1Qa1of3QbZsd!&% zRh=r|NU&Xy6yU()PCuW8FPs%R`E#OgmBR%d-qhF7LQ_JAfEc>(mx7NwUhe|3E!4$A~3!47p?=4E_?)t-7dkEvxk$>U=G=rQbIVWU* zpN0OW z$vj{T2YGNs#c&)OuBEy%yLe;eqDz~iOODRmNc)t!KC(Jn)z6G=S-xmFCqTkGw>wD*>lhuE747RXk}a14GtGgerf2WaN_Kc7u~2<5 z`9$O~)n@(y-NQ$fmQiL~F7EEeW1izQ2TufdYMf;Iw8V8ff!mb|tZPfTnLhgV%wprU z8aG@6*&Zh*(pbHxZOF^%n@LjJ*|@hNf{=h;F`2!(1~vQ;ht&hqj|E=5JG6~%*Y;;1 zKwqC~JsRm)zmYnKLU?@C?^7%-z2uh7=B7xpnQ)U!>-0M>axpV}p@$4G#rkWx+}*JxYpI@|m}UTQs36q0%p5YM{e%0B?_N!HNu6S9Dp{OILjQ4%kYvKAoL8}+H<7|uM_UmD?0F-i#h2#TkhCSyRmGXgIcdSF%&nbAc)RH z@Ran{nVy@iX@_qi7T!tnjFLYVb?@*@i;|MiSC0_Trj9`WRT66@R-jjS0O z9-#(c!hU}8wx{f;1PS3yzOc2rmEYQYlJeEI^{kS+-%`E@)R|tj?s7)d0M0@$DjDS9 z9&Ekf+y*mml+9O>8H9;CmdE5B@WFYH_Su`Io|^vqU-f_iak&wCpbjQS`M|M(_T}`o zWsJ`Eu|p<0P_>nvHD{TJt&BNSW+zAq-bA}v!wDBQ5l z@&V_Rm@9nO&drFyG4klbV!4}y*9AQk!-;saN2{+Orh zyxEe1E3-C#LH}oQ@m?O~4PgilY-JqURMObm7QQ#^>$7USzRgaNeyzzI-N??0-po7g zGlU#wfTr&r{y9wVYs?kbR^BnKoNvCZD1AL^xu-viM!58wQehjnxvDLGkA}vs-M1)P zE!--3R7Y6Zfg^6c)*%1HO(PyW}uYyH~C2d;PxF&|Jvd`atFw@)U zM!Z?hWM@TtgPLr_gKZ@-z0ydPGT3-9`5y|gL{@gtV?umo+c#E|I_o(~{1Qq$l=?g? zN1>W(=J4P^x3UG*Bw|Lk@QAu=!AZNnUScrt%w%}8v9YtnJxRwjOowLSk)`t?@9JY~ z8}Fl)i~_AWaT>d_0I$h-*Pm6WYK&3Cj&QFrwq?7)muEqYx|OQpGh0GXdv?%2{RZ#VD<^KyFqJN$UE zgI(S-+0rg=E_|{?v15q@AMsM`Tsb@VHsZx^1T@~AmIx&6SgZH*1tECDc>0f?hB2tu zJ4Y-B_3x!D{od6r|6iY}pSb=SE2zvb2i>(-TlESIrHI%$yhz?x?j+6AVr&~_x3l5+ zHy>OEVhH>nZj(}3JpIhJj8Ad0%AzW60o@=+*WtOc0qAQ$iR<&mIztNAo%Boa!BH?m zcwrn_1LmJ(pf|m7SkE~4jVohl(LNsbAdTt`nCydCj`nSh0>A{ynN{2e=a>fZbThxAQ;6r!`P91E~vNyM%J zu(C)SaR)|w#XfLQ&(K21mv~kWS=@vpRXnWmdWY1~s$Xpxi+`PKGM6D0H6duOccP!Q zJO7_?b%7(Kd!{0L{P%z>6gv;6r+!X8u?r=R`}*CN^`fGPG=d~QoKE9bGeq^YB*)_PhulehwfbgJ)?4|SfShUBu6rgs(ZxK~ z;uT2V*wTg$Z|gOU?fOsnQ{FO=N?8xUJV3ZgHep=SY(|$v*cx??>gct8K4~?E#ucct z42oaU+0ny8Z9b$s7CtW4myrABR(pq1zp%b2_Qewoh$?4>?k8@#D%GllyROz0-*MYQ z-l}#uPb9i8ulFH#&jM-B{bJEwmuxmEfAW)-ox^&@;h_j@^Gox)*7}(66v?Z2!^b2p z->>9m|G6m*NW!|{iJWg-53`XM_k!LzeD!@-%kWG0JQq)!Lur)%_EtTBJ+BDZ{vnBZ z!DuRZy3%0gw`2tfn6*~ul-NntbQNT6`K$DLh&`OHA{P|$hxD}!G@PmnmCLvpgB_{F zrP@()l3uabg7kt5PDW7(5Y}$FHe+%yZs%LxCi#b8czb%^=*8&He`3by`vQcRY{rNd z(%rsrM%9sPUrv6L(@%>xE7+&~OZR>U9ESEl=~A91SeP{6-dD;# zgT?{c04Mfwd8^JpARiQD$l5mZ=L5YNO5I?JrtSzWOO#a`!XWAqoN-qWdy^~$)uoq* z+~TaKMsu*xZgI#FeQ<#Q9_>ZHHf@q&q?OTE=qY^A@FkzB&w=0UUs{~yFSjw2I=zq(Ba+!K0GVjTc{R9anq_*jG8y4N(@D-j}a#q_H5}A42c;ywBNh>=L~6Nfu+&BzwOzqQHSXJ> zXl;hv7*r~@@to5>L5JO(pTY$m-WZ`gfeA&=V-n+5(bH~L!&2fB4Z3FE%1VhQ7t zrnZmu0cTauHfoSz`O-sBf~h<~htI=I^w~Zn)OSIu<};%rFFvBY$56E2c;}KA^zqRr=`037cb)#Sh~d+Yi1gg zjFKj2>_gqihf%*m#L@2Ly5ACJ6QK9_FRZ?A6qrNVgn;)(k7O`S-%EJDl5;-d-P`$2 zeR6)!P<1m5y3XtzAuY^8Gb0Uuj;i}KSB%gC^DJjM^FnT<+9A0*NzkDEY`?aUp$aNq|pLefcbfq&33$e?fd*C0i#8RBpf|vAHdxS+ojv zP{g4Ue)ja36#08F`YHS8%(ji0PMJFS&u2Mx_qSpg)r@ZyCuf9iD_RFUzmdP@PhMh2Wr$=_#lxzk8*LYQWrT3hQgSKJ%r) z>aKS1yrILs0x$$0Y0!cUacvg-(W98?sGXfr~P|?&%8*lm3R%kM_~pk^?c>Y z4K@vr?#FCY?&6)?aB`w=YAV?hceb}gF85a=Ed!KH9nD1+_$rVdRN{XFpVz%%oIL!y z7kRcvPn^(^-Qkp*_w4CrA$$(d;R{Jvht0(R>||wM{ZjJsi%<60;>+gdU{ODI_KX37 z+Nniz(7JDB`)p}ndc$z$>2eo|FvvQs?U!^80hiYKt+X@FF}th%GrkcPe7d!xdtb#i z=`sKJf^^;3X6&=gJjleifR8PMD6^XTX6gWf%5*2a2|WDGPl+=Wj=f>{{s7X0zsai@ zKfsRu=0-0GI@n-7dGYolWAOm@?TMMv2jxGFZhd9E_R3Wkrq&jj_JiJAH{d?Fwz*lG z!)CFyw*DgE9b(jwL*~G9wyjK!Pp+TxeVr8izJRh=z0)g?&{ehWUzDh2F8`S6gZ@88 z%D~v_Tl(=^w?Of7e+Kv zAR6TAJstf;5T+D8}3DD ztXrGUEt8DgZZ0unbot+Et!n?bg4s7>=r4c1e=c3ksHVcWO#Uty8UDw{6o@3tN4B=@ zM!N#@zPwrIq;H3#1|jDPQ$I~F+9f0J!vkAwnnUt!GPc&w&JvN+70Agj#gNUX$NL$b zR=JVu!BJW7Zr_}$ue;fA9aYNOgmNkcg(NiG_Tz*@QTCw|G`hWg4+iqr%hGy6SbEpxF<<#^X>5YqNjW*2Rgg&Eu%HUFJ_{Fj)VSxRnvuOZ0 z6fE#6{x+@|^c+ZX$Gaow72oDCc!9?24Uo6vhsu%~{+af^v+*_dS4AqKmYZ@DXpG9R zC-Q93rMxx%v=qygdQLW>eryfgSCcg9oyl`U(Iid>V9EqMa;!U_&<1hCnFM|yopO3(f(>3ZO3+eSO{LYi1IPsQOwEQ|VxOAyWHXzz`gMk#r$t(0 zl*R)}IZk7Zz(hVkWx@oDgQm;=@r*of{sl|dF%fwZ)$Vim9-KU!H92r)1uSd!hEe3v zKDbEqyiI^QbhH0EVmsPJDD3owy22d`H%geS0Of$bp-Yg@cWJ2I56SBAL;t81-6V0t z4`<-_;E|{g8ajP75}NQ#ufe^7)*Uro)GLscCc z>nF5rz6@f~&*HzM)o)RSgm)~f#LoQ@-ueTEl9|u@(WAJi$rIDBw=x*97IT34g3<873RS<^>&_k%&Qy}H2>aUH zM?|dO2%$sqBQ0u58$P^|M1CXzQ_N3J7_HZYr!mQJnj(JD6Kgco79JeHmM#;*}EbTQ{v2=W)BbFP4Lea;?M~sm=fsEp-bcuG4TI#yiAcLj5oZDG83rjA z{~A2ER7wX8$5e$+p>rt_Qa+537a+&8Bo-D%r_W5*iY3%|U^bp$a}^vv(A&UlVG@#^ zdwRi4x;c;a;H8L~sBP|_$vA8bxC;lR1RLz|iNZEdf3D1o6V*ERYNRFEGCzK7aJ|Ms zYm&uM(Hd}Wr5LdJtU)FnY^&W-7IuGJhkK2A@qU}&tzLRuRG$S4B(lc%fsYP@ZM&~& z*?dB54azrk{KC*odp0V>%$duz7aWbqN4=q<3;FhB!4L5Fl{RT~hy4354D?=)b!6vH z%3W~m-_PBLvHzu%{s&hIBDC|*mH`oV zGz($st;%zwH4zbOvyc^++*9L^X-n|12e7creA{tVbzkKkbE zg}h{X?pYQa{8V>tKc#4KDB8+=>03AL(^^%-C!D5Mb;N`E>u}LW!4%+YzOxWWqf1)w-g&tUiLiiVlQlYrNbk~$OM85 zEels71YG26Hz1cPtxCA9opTPGT=yns1^^=<5cMwYlr^k%yNcb$1W5X1&XjQhkBT8W zx8B;VHT|K1xBG>su?DhyM#X#Y4?)GOko;>g5z{i&s2zt06zx63c?`*MNJ_u*&x%F+ z$Okub3Cnf-2HAI1rCX7y&bfW-Y^;Jk?#(l9j(|5WK3KTL+GRRCo&)j=PmEQiGY6t3c6v(DTYB zRC-p#>x{5s+03fJpKC`M#_cVV9=x?dGy-oiTGK9RXg*q5RB9+@wP?#|bjmPgE4==i zRCU=)P>#yP283C=JdixPMWQM{(foRd7}(r2OcOTsGEF%N){sA)lt0m<>HAIHJ?^^6f%2UWyATt`Cia_Xz*|yh!I?_@ zNLi}%r1FO93T{7qWp0?1)T5O0#7Co)_Uwi}GdSKt5#k;7T~xHZc9U1y;{KlQ7JMe0 zyfN;(zx?QKT|=!<`7@-{*i|fjJzpAGLAFwRs_|fNpuDsCWy?2sid!)EvqDXQz!?GrXgv#hrU?dOB<5Np4}JQ3Kdc z`*YB$ji&H?K8BWUBhY<{zGVCsKAcGT`h^+?n`;;JhXD@7#fWv$3K9JTnw_!?o_}5&Er%j5Sj+u;kez?*m-z~8uwIi^ z2ILk}qJ6KCB}L$%g)KedkBzdi|HBjRhX_76xLSAhL+m9J-oR) z;lUw_D9z#IAd>CHc?UE-hYJ+Na%xl<9^yC7x%9_d%7?*2>62zsR7}u%KCA=KJpL8; zJ}svXX)#5i+x~j1JXb6DZI8t0)jG2h4yOWG|1l^Mgcu+A*tEwoHWO~R^_qSY5fPu} z_Gx0KxyIHe85mc_NdUL-7K$GJFL2`bP4R$GpTJ!A+mJe5RD^BDN4XxwzyMwPX}s-R z>%M0&=?lI#iVe=qa>ly3_3q}2Ct$|M55Jf4=XMfSAuHea1b+!m$udhOMWx;L-Z_IX zre_Tph@#%`>e#9VUN-xcS%;4k+Dke3KIXFB$sxJDW)xWvo;HQO2Xmn0@2LE%`+S@- z7bbNt>^MtOxnq-kTsa(sg?uj9Eb5RNOa0VhA??UXze_(Z@9+DyIOzHFF6=eaO&sp( z4lPz!AGivtKxJ^s{}JDP$Kj~;_-xhLrEUJ|wEItetW0>%g;5=t5H+++T}_Wgor`kB z)T%k}QF=ER;K2&E8P@V6QA*uF=tFhG4@xb6^4VpPbC@rt=cRj8FYAjM7Y7v!EP7X) zVFJA5ourw&5lzKaK&{*Ez!%;Wny2^gD+`_mNus307|5y~3ci0bK?;iZS``=_THD$d zm!y&=8VsX*sQ*+RzKv&V5XTUVs}8TRNNx$SBr`e{3-jv@~X49k)6U#*%nKv#cSWx!}qiH-s>AJ8#TJzuR~kPu|Yp%$PG@E z;nvImHx*hiyR3_WKVmpye6FpdrLL;FwzIZ#|Fq^TLadX2@US}UvO}f{#=we=17A3MBkL3uxFY@6-D_}(&}>4{S^6k^$cMGm<-vtsxv##a%_L!p1|U3KW%M6XkvfVJ4K>WAQ!c~osJNC+>MExmdNuh z^TCzi@we%$^}oFuVv6~s{1K;upDEIBzNk+9Vo-e^rl{nt1Nhka=W7p8v8xFQ>Sr?{ zY(!l~v#&0a*$R)X`p`$WzUaHwlHcfX;Eu?D+g=Su>ngGzy{L-D7Xd7w=_4YD)@u&kSl%hPoQ0 zX31AI-;xrTmh~Mc<`{1_LRr-$8W3rcLc}aR#bCd)?$Z5(ta%a*>JH|h%e|z!+ zq!!h}m>t>FMqcISBjGL>8ay%(C+~@i?}-XfCdO4(2YosYD*D~nD123M8H``P#C}iGP=s7X(AYl+w!IZ0 zs-BUS04TVQI{bRf6I-+ZopoUUwfJy;%+q?k3>F;5@e1Xs@w2q_(PZ&`sFJYht#JLU z>D&wJckjuSjdRy{I_#$ygqGWqc@*tTtD-$DM2NF%^Sl*NtUsl@oCLPdzSw;HlqvW0 zX77^^Pdw$ZEMvN%7D7=_sjk`7fwUtAYL)+winsoX0_wYXCm28m7?f@hm6Q-EX;Dy6 zX&AaBq{E?OXlYTpLtyA0Kn5738CR!`uIGK9cinq`+2{KY>~+@J`*XhT+=|F| zuB3^(i!vgq`Hljc5G({fT*@!THiJi5#Ko!39@CAI-F#e97Z9@#+cIFYsm-;L9UDP; zD=jRo>7dLS<_V31&C`xPT6)$4tQ&hy4jH=p3e6c@h=RIBCB2_wlhe8!qga%< z=Xui|r;5)miQt+B`cS@vHo#aRrYKI4;7^2!X2;h!<4ZaFsv(-s1u)L7IP* z`hQZd+RYkAX*`#)vZ^S)i%X5oyF~ld&kjf_`p!&3*#XVoWGAeZs|ToyGC!bms@15(ojOetUo&= z#ZSd1`?ueX-x+1=#-eTyx@$}?WUGSAa+*d_(xD6+ZhlPo7Z4p9zFHb4egiT>*TIx4vIzDC!Z+Y*Z zVa|!fLCZG*yDeS`gqw3dOahDV3`I)7n~ zWzPP-wid_7Sq&Da>HMWg%+2@k{@1Sf_r&O#kPxdMV>0<;qADZr4vdU&#tWG{9t$Hz z+TdUEZ)$#e?^hOWlwP-9_$+NUWv}}zU0fJWkrB%T?3c;UIgB)S@VqpT1N#9ngjqq6 zh6oRr%G`Y9yApS=;dC1`lF-#l$jVoysyd;c2P)U&-eYtGrK_o-5PVDl{jmc6R8IO% z2AS4mAa5PJP?v@9U#+0%rjejSFwL3j$vsEMgB}RZ?^!rJEnkAU+u8Jo&k7~BR>PKT ziK}KE9G{}P9h<-iIjdRixwK{j14;6hK^@I)C#p6=4?oEctGy-Bc5iZ@9RNZ-7M0$h zwAVs}R5G^UPE-#xH!FAW>LzC(w(mmu2mFf`x2 z!`j^sCU@qRlc)yzOQoJ*6(z*^`;B=;sM}V1V(W{t{Pp`6J9Mh~c{T;wBrnQi-+Iv| zh|%GU`Epo&Zd^7W5cbBarZfUq0F{7d>nw?h;SA}$R{J-7zaR`AB>?mYTae-f>vqU?{Z#Vt>*nr{VQI90x3_wxPv<1W_$`M0 zp5)k}^uT;>@3a;T?+zI(0S1k{+~2mZ(dA^_{}*#r)ojFPWb~*;u|Da zKNvt#tg_^XvLxKABRAsFQ>i%d<+G%{+O4?#Y~wO4h+?-=q_T=4KX?wlO95qju=bl) zBYtQn`u#N+x0p#(mB8|Rjd1i2ta^>`SyAZoInZwPqKwz^QB~#vtb21Tzh{nC<_<;s zd*1nELi8+ITULHC5n8GPs5B;l{v)Hpt^p=}=D3iScfJVC!_=!WO~ZwNGF%+uu6kc~ zV^`xueuzkfb=+6&ME=z>uNW%{;6NR)*&pK_OU*sTlaM+l6OyoQ(1r8zq4A|Z)_a*hTli4;z=gvZ& zS6i1FXA)_7AqytwXnbG3xAk22i@y_dC9Eykn#BAc3lOkOg(E-~M8-X2*snSW`2&9` z%x|y9*c24gP_NoiU-4x_Apu6LLQ0m?teob+Eq2Ja^9_(X^6KV``mYVO3&r6-RlVJj zlPQdk`K$L`hBFG~MEk!>_;D0HyNc0v_glO|0ta-6BqPm$Wy&XU_;8IE_Kh4wF5{`L zb5@enSgaX0GBaI!dniuoI2Y}zCt=k?5O^m1tk@TQO`odMx~dTDu=`ajfBI!Z^?3|q zrNb)GlNL2oLz>|PMz$W<_98-B$=FEm$lS!6hwED*K-?DbrnC{&S=2UN|*vGJ2iL^U5Q=y>a4luI2!n~Z`6na!e_2Gq2JwfX#d?htoL$=hbgn2cOj#1)0uftj4IsFisBX7GR8P z{Lau=Tb=`MVK#Bs4=O_g{w@EItuM>yB;l`N9#Q9|Vf##+K=0ErIPraD!|^V=;fBFR zNnXS*YJ3dvnRiQ@g=(Rbf)+sYQY~v@!qNaS_hI%dQmQSXNBM7-TQY*0hfKCs-=wi*!tuN!WMOKFuq~xS}$i-QNhOWY|flHeAnS~TBD@6}@ zZiMxt-4KTRq)QU>j&zejB!P>T+(=#PGq<?3iX+6Gx3-^2#qDt+{X*B3er8WCQO9k=L|ANP zh=*Peg^RFG`od4l{%5#o_rH7XLHJUhpViY zy~g6mWYK|G4To6`uQ)#;t;c^U4>e7+CbN%*}_!hkl!H}C=1}sxlbYuV8(s$nMDo& z%L3osTLrz+tnSs@o$qF5m^E(LRDe8pd&lQpJwe914QP&U7H8vMVn)iD_XodlqGUBN zRpK{g;Zks@hr;)j&103)tBU{)YcHsMpQXSC9L9g%TUHl1W})c@1_Bqko^#yUCUNgN zcgRc~{qu_Fj&#dlz!b|YXn45!wD=ur!s>X5>i)CbvJ~0;fR5M3703wKv9`C!YuPy7 zncdKrv)mk}K9ux1e<$g(qPRKzzS)^Ci`8d0;yj2}YQ&_vlLiGNHipCNT*dh^<0J~< zQYLCFI}t~3^FcvNieosqld1e=7eeHw_tHl)4tt-HZ!SKL_>4#1^EILa-t^@5i%}=%+`5 zqVwCZXbJledd|ANZ&avzI-fW%$h3OkQWv*<=uZ~!WFh>2SZ!3mHZf-B4xodeC;(+q>#=qV5H8VFyH~NISE}0ANBsfH-nTc7JPzce_!ir ze!v#8NlxNI`<918+t7UiW8Q_0wDb= z&1;lyIc6b$`3%Rr0xEyW&eSi)3zwW%R{404jYmL^hByB{mlEyG) zVeJ%OnS>&Z6cW?01$R`Oy0h!Q1x(ldaGP$Vde}!D9}`3~BZ!sii`MNN%y$>;V0wuJ z9*%}km9D-(@8&3#6HM019aga&=I(Xu)e|jEXZdf?x6j@SHi-4ZIW#o%WP84p@GP>& zy;~44Y+Obc?sNIK?e7>Dc9DInXwKXkNO!bIz|`%GM2C_`Y^#W}syT*&QHQW>CM@0oaAD`@}=4(Ey`syfij_GD} z=_X9`0|W$yoEnV}@ydOevj>xPB&A>)p$w&`WaCw9_hU!m)AfatuBni_8EB)Yj@bDV z@;}`(BQIaGcm+xLM;AGow8Z@K);Jr(>N0N;ae(R*LRVdO|1l<$NpdemAM=2FX{l(D zvO9bz#`A@>$K=`pr+@l?@LGX>WnUBpMRq^PzSfcNGUwLJX?TT-Mz~X4RO&p4>@1s|JE-|M z8^Rc_RS2!!B&&%y%URUqxK24uRKxeYq&|0Wj>BW*-1xOzX2|=08TzeY8+r?`pXix@ zM>j=30-xeGXL^Acnab9-AFqk8XN;-slOd`(>dLPCthuf5)Cxcysh!9Vg`fGUErlaw)HcEY zBe-*4QzhVyf(9T!oEnR0sTHWaAV3~8?M&1lWCWV$PaGWgzsdJD^j%*mEge(tE&3R9 zc>+pWEwnnMGybM5OYr5QR5O7{JD_oSIq<#1qp!Rsc zD0sADJBFzx_flAjAmwxXOT%~IXDcm@5hG`xv8Ejf)_McxZ4Am%05&Y=32@WyQ{{ln zpGooZXtF+}w9Y<{5--U+pxQFxMR4~Z>|vs_OrmGu+m%tdF}4ioklFVafjrTOY{B zNz#!0$gFc{oFFIc*ZG)l3X8JXY?$!D+R_N-I70mO$40ERQ~}&Qz>w~Pp&ZI&BzvL| z)!AQSIUhG)IYCpVdXeStqAwHQne<#|W;7=^#~|PwFwZityV(e=3E7Hu~9I*TGJK`aPMLbt<}EJ&v@xoG;xk;Ww#V^A>*~; z_S7TDGk=w3X}=6cX-@XqvGjXgzc^#q@rsCOqAdlC^`$O2bT1q*7cmLzzsYZ$)=%$x zeBBciqNY5sam8q~%bY zDRt?_7nRw$Jk+c5L4SMjQ!eYT6>aJ#`YjkGAVZ{`9vhS}Pp$5C!(KD+lqZ}0kU5(@Y^na>Y!~6zn4ECf-MmR4CZpH$T7$!=eoep88vWG^LokN7nGhKhPOsfj;J|RpRo+FL!+?L{t=LRpQjF`vA9E-Zm z5098ovB{Q=pd2zwJw_#3KS`oFD$qW(y^2rY2^7S5NxS(|rZbY4I4->Kv5)p0u7)G0 zHy_5SorRY_KR5y0#*%)Q^;)o%lpXX|R#AotBdt_`7C}srd+`*?ABgSKQ=)Ws3K;3e~_8YG+0@dJKAN8PqxpYd+ zxsXzr3)6_9Mn^3h(n4|nZ*TT)#>nYCY2l5kIAh@e^ zqSmd6E7&5cwOk6DterHF9?zjac&oY)UUsmFzrbTIUNp{D&Q@03ZC@YQ`QdeYDsi=l zfb*G?(OPQk9S!k~HCdK7J_=S6snWF`^BXm0*XM56&|;PuiK`sFBM`uPO9_K)tTw(4#G8~_&~9i0(`v~-r48&mcS9J6Iu#1*dn#9Rem{R1Im4n9;5e8_rl(;pJENqV&fB+H(7+TYvVddsyA@eTSaJ`GT4~0H?QfS}sPA}7k{$Isq6*8zMhspSU4nnrhR?@y{Cj4ae zT9~U>FXcXZ4EwR$c3L#w^>H$KrNa9V6ML+KbCLe10xBdV^UiryfS+-ki;^K|(H2F& z$Esvl1QOcnQMKd}K5-luV;8oFJ_lX8BCGskL#gWKer$h84|!k9K+I^hc|(1uC^9f@ zjmcfn_VHxgVcNIoXLhi<@yfvEXU84#RkCWb zHVgK9QNnQN_FD%rvfgBBbWg~30~f?Q+U1xbeW3`I=@X#{76f)AtnI&l;tkZk4P0DIk zQ1gkx!}Cw;f;?8c@e06no&I~Sfv-}9rvYS%6?^I6N9+E=VuDo+iIwscwsO3}kjpX( z@`+~?1Ky$3&$maBCO27=Lt*707woS(5;Sw|4m5F?QQ2&jal50}jU@U5;y4YU%ag)g z$)3X&fHmu4Cgy7_NT<%FL(huYJ9R9+U_lSLlYd;_nve-JW(s!G0x*;)`yry8tuMk$IPT#ZA2r_FK<&gUt01sUAqJ9F9~V38*) zW7YaqIosGUWWQk3wOx~tCYISaro8-i9h8-vcyhGLnQ-TUUho}wTEmx>xb0TI;CnKp zpWxhX8qZWe?x#G*Imn?{w}aV>g3YES`&M#EQt||BxMhp%LZ$`YkSR-{cuCYsC46p8 zFZLD>P;MJRgwDSkGTU_e&0IIkaZLEf;wp5WSyw|`i+kgg_@VvSbw>9O6fumFbE-?yfikMk1 zIu+MMT9MrvHqm7|8)cS77w+IxS+)D%Uo$Mk1Kcd4y(+c}aw0t+1EdU!v;2A_(5q&1 zZp`5>5YxxToevWS<2e|`V~<7cH-SI7b~_&6kP~=|AT+8$g8YaS_sPCf;VT$T(UDVL<0)FGKu12PwD%(rtBEVa+nA-P1)9Z{CM%qdI zy&S`-WQ1P}IC1*LEPa7S^~_V|NPfa%b=5)&;}`=A!yUJWaV>S zV;@Int$;1D7q-6RmtQ2+MP$css@zVBt`%a!TjX-C70$x9Vaqed9wq(WU*LJ0g2Zx7Pu`TURBQ*yc2IwvhmaZK)he5~*V=l5@m>hHGQ&oARb7 zjc@!-jtRg*NVBlaAa*$_nTy+tJAd5J-KrQ_9w3r3$eIX>+e&6pAzCcfI>cQqfb7+*3S6W*vreL)AcFYN3TSpKiFI>3k-L~ z5Me&R}I1v(@ zD>4t}awFoQkAYvQLaBYaU@@|p$AlM4Wq3!q#hb$1?ScZp=gMxj?AX)KpOW>n^ACa&J? zWOJ^aJTSb6gH@2t(_T>!KEf3UBWJa*)bnwWbX`_twa}@e{qp5Zz|!|Rwdlu2%UH=y zhj2K-V~A9Nc%e}sHoU;S$BO=o=RkP_mkgYSXfPu^{lXf>=w-!vJI*=FEa3gN8J}b@ zN7>IE{eX_x^UY-MxbWW!w*mbK%t}Vp!v#k-8d><*++L`{Ul#NH_nb`)lQX9kTS6Ju_pEsS)2`Z8sesV=3JhE+GQYrjQ-3H`Ym1 zlN8kEG{p|!IL6;*E3tpT+eB4?V8p{2uXoj-)qcU2Se2&cucxYT)l#2x{;7hD$ z_^Vy7>W!W>R)s$GCDQ)w@ouqs?(Uqo26_9pp$;Z<`PVwLVdAE)ZG&^UYa+%n zuq^ewL-w>`_9Ea8RyXIwDwgu7V52~S&kS5c@K4iNv%UQ7y2`>=>gVSpnAkK|<(y!m z(M|~gN$egxAAf#_6PRA5hFaTMmS%#e=oQ_Y^_EGpfgvC>b^F=##;JGT8+D0{YM^LJl1;c`*2YY0~;*cidBDDrYO!`Vy5VV+16}sM49{3V`p6m z$Wgem>Tj-gt~Ajz(P^VkjMdHNHcIsNXVH5#=St1$Pk80dvQ~)(JutnS&=JD_qScXyAnE~qyxiN zy$}9|%T5@d|4y!V+k_NWH|vnf;I2kyW9iizYVw${r$nXiEQg{VyM=qMaT$L#cYnDW zEH#75QEvyiG!X2--(zHw<6WlrR2LI6(yzPIT2HEdiw$8Qs39IUMcuAOH2 zagtH&DB3tR&TtWrmjl5(c0pQLC$67;W{gmQe^Jv4tTMh@Q6w8=Qhj3fbGC`xXogZ2j1uv1asjp$BMrQk%zH7#>Ll5J*^)-NmXaD%IYC-)-8Ch`sV%aC*kekc~`wma{?9DuJGwG{z2>Lr&MDA(}c}apKh|V z?q?Y;&qHeTA&`fE#LVrXpg5GwMMnJVpzWNSHr`DLG7;=)MB(Y64uI>70+wU6>%+&} z<`|g)9uQ|E*@?41i#S_^Ke}yr#P(+Lvit~FROz;JtF&;}l(c{M8FCog7N+_kyM>_g zKY8LE%0>PEZI%C9FIU}d1mgC+>RkbCni9x>I_bmQxN*dA?GGJXsdNK@=pzBUr4!cM z`g0E1krm&E<%9^qyPE5kb)eoTZ z!UD7F+#3gVzX*NJy@p!L-FIpFKDlK^zS-=cCQuH2-W-upffWiYx@F1fm(VY$`oXs= zjP>Xw=`-PDOiOB%^W27zDrQ2RpZo(3c~G}^ za!mZm<$q7jt0uta!jnbG(!9(3qp1G5U^9`rXcIGW-V+_8FYI1%cgqTGQx!}J)RhU? z;MIG9;S8dql5Frcl|S>w4QI@e@@viObb#Bc4Hlb#tFsGqz)3Sqzc><CfZ)_qZNq`N8{C&F(EcqyaI_@sXh_rFbD#Md-woD0DO_&=G}RO zT6t!ynASgc>L%7Kdb6-~TR3ek@k6SLc&IpE^GVNDro#+Bq7=*7zX3Sk?zr}a>p}tf z(-1kR`!|ymItm!N-k}Ej9G`e`$!Dpw9!YkQ0uZYJVb{A}%O6C13cS=Dj)wwNMJj-` z*EE*c^4`9||6>92((s!6u>*~{*<(Nn@~^VnL`(}+4mIVeXObkAIkIzV)}=#RK=16U zFRu3`1(emAT-BA=xMGhwq}rEIb*XJ-zlg@oN8Wi6*hCbZxbaTL()Vv<;pjrePRN|I z4VTB9^w&;xyn46Zwbh>avhIBU4mz3LoG*yF@77&St4rWJvPY+|+M_tPVq`tLeUqkz zEsY0zI_8%P5EG1i2g4~mwYTlHu=;99vQzCQA-JW<1^Yq(FF9@p^JBJjwzS(}$lyO{ zMiuKupc(+D;V}}Kc-_3BjyKa~*I3Q%R)`5_fEAxs{-;d)-&Tz+L-oARw=o}Z%g&9I zty2PGRQua%^KK=KjrXG}1xD(dP5hjE29|DA=NK0c-)m5T)GYCQxsS*@n@3&cOgUUl z8Lsac1DpVk$odd08bLiOFU?q0z-vS1Q6+0^*LJ+`QLpN|{XOgnDyry7V7EpHgAF;I zC(xWSBkb36z5+7cE+vgVTezJkgM$ zTrQG1`SYFZ<`irauC)1vh0J+=U_tN_hz@)RaF@(k5Q4r&cm%iy2p(B0Y1q!`r!irW zf-ME4#e04*d_23L`)J2%|2;n5fAEfi^wtu+7WS9C)%W@)~>U7Vuf?`4D>Vq#1giX~c=;5r9 z_Ed9YOPoJ~9tXJabOMW!Z>X?ledR)ryHL~@jke%P1ZhI?t}NA2uG-lO@OZ&|q-_uQWOT7&JDb{VTk3C_MaLAA082Rka z(#RaeGW~@5k}n$jEuC(bfu6c%n}N-v1DAJ@TV|xSxYk#^<(SIkzPt8hvxU02pfC5G zPlatY2|fce6zw!8H0LeRP3)4LP(zOpz|;94xNxY+&~a0l3bAs(2=y=Z^?U2IP^z*A+GEISCQirn|-jGe6q7$Ibm|~=gjnMYP)je z?3M>|$crm@XB@r$$qAoH8!9QPkAGNwd#*o`8MP6q)Rq6AM_HPHCgT6gPnnk3S;)MD z9A2mZZwGV)$=+B3NpVsW@&mE z_-a3n%K>5w;Fn`K9wzLZMz=g2y_XYD(_S|qKhtX7a~&6O&N-*2cbd1-%$M_w`zxv1 zgC=KLq8ea3so?w(_<7CyU#i$*w+a0chJGb~i2h?Ka>>nJn7!bZVS4WKH3>E+-<}-w z;3|XnezC{&v^&Icsc53w`#v4fDPe_qD%2iCW58be{tHo)^%XynIS}sEn6W@2@mH_y zIk}5{oJ%)*Abr&kQg=P{;)?!^PucP~e%4$9a27jJht$*;pj6@u?4ddt98&h0u9R;C zXkmW=Ot4+kPN)cBT|2H=VKFzPIY2x_<^=uZhWrilRivmUA*aUn%lin z*Bt}9y>?ZZX*BH3y%$fk%h&_~o+%kv&6)%0M-+SjQsS(|7r%{bJayBX#itxwuV{i1 z0JdrqBR%1djLg(hIrkU?lY5da~9CT&?s1Sf*P)kpq| zLv>=C?osqqb;AgRHE0@L2MhJ%3EV0jv`$S=O(8tA3JlqJBptpYqt!P^A8o-~S#7K< z9f5=Hd#X$NZGT!I&{)3`zS^S6j9F$MXYGsdUVLKp!RmJc6rb{=2 z>hdw{FwzZBX+#3RRM({wT}B?)gWD@f06z9L{Xg~_US}*od08e{Z+$nFCQNKG3I1hXa_aDHA`x<17Sw;T#WbS-4t|ob`G7dr|4ZV#Pg!^Y>#mf#0Rv^e=L;#bNP!~Wug4S$d|sTbnqUx6~{n*v9)C;8}xZy8#r za2JrL1`PuxI}rFj3#i6Eb|yKb+@1|N?f+XgLLtzfOyMM71yeCWGC2z-)W&PlUs9Wj zZbLom5-Z}Ee@sHbRoO{T`Kx%0dlV&i(ZKjq;M^I{leJE=%PBXhX1?5vCl#GNa!W{6 zbSJ32)6DS`+Hbd(Rd=*r(3FXo$$gaL52)==E&)sGJ?+El`t;d76#=`BU=EF1)jCM~ zG&}f;Hz?R{uYT!s92;H{*U8E1k^yW~ieqsR{-*1$?(DH~7>zu#ZD3loZ$XI>(i^nYHyG_GCO{CIF^sg*h!YU5k-MqFQ=9E2hoxmSv zdrWwm0%1QwkyiG~*>9cz#W<1@V~SlXpM-LxURH}LGYn_7{cESVwcrM2-9unTYZ+ia zXTu#6aW5zFSd(!30anWmOtXjHU99(FVNA}f>xSU+SS^{a=Ax8)ze~TFH;*+x0?M&6 zT5sgFZkSrD_lMXg_w|rEo5(i}`c7uv3nQ>BR+>&xk})0s1*8-#D zT~XaPuGCVuCiZZfNc_oF2=}cu+L#%Z8U?sti)E7$1*uhj=S|7zP_KmN{8~wCYW~nP z&r3T+5Lf`v;a?V+k#ph?19{p}OFFkN4Z#ON1pZ0Sidu^<)-OIU$nFiNO$3zQO(IrX zTO7;0$~LNZ5{dTJ0h`LT-urg7xc=ryr7n)C*(tY*(vraRoZ_5rf3BkEW|#2IciKLyCQZ7B?8}wYN#)srAA{E{Aoib$2fJ_- zScv$e6e~&i;(Kk!aB(?Rs+{4es51ez-#T5>orE?_3@=8rytn(#Yn^;bb7P)5ytaQr z;P+q_Bqy%O1yeY)EvR;Nc#&Mpf_>ESCNa=2oQIZ}@+vT}2%wQ8?Cg~@N6tC#eib;4 zN<#4Q;(ki=u2tQ@@3Zd^jhqUvZ(n@LYL4N11B;H2!OeAkia@ea z@)X)gyZYSSkSk^z)Zo!84(O>0&WdPr z()088nF(~ND@kT*R+YI5nRTxlVoGz*_@sn)eBoe55M zxrcq{V{r}WNzKSW`^f1F#cef8adEJTQuSKskT>tqSMqQQy%SH{UaZom$(X1H6zoQc ze?9Sdmo$X5p&IA=1>X~b*;z3!*{=3pyuXX_RDD|@ITt8J!GJsLoneHUek?9KCt3@G zxUWqWEJT3&9lM9CVwJKB$aisve>rs2YjYmXszg0Pp3cH1uNc!f%*n!+>uIN|oH>qT z|Ai9VHdbZmfA5NVM^sRc2X&TXLDOI|D&&*E5C_E}~U|lMjRUdfgnK zw5Yaam(1f%FnP1(vktOZFx|Fte*-*vnD+MN3HHSJ2NTw%JaNkKX!m>N{(a*EUEh*` z@ylsR*!YdwiG`nRr}Ejgf7wCLe`P+CsG|KO7|w^_G!{nBprNWBSKodm$Upx$3^w^qrf8s z`MY*b>>yBn$YH(U)s`J3=bTLKFI}AP_4hqm|D#PZ4)uE=TTX(YGRzKE6kzKs1edon zm{nKcz|vxQmNRqek4GI<+I!A{F&+Fg|7vt&7|)37?WP|8PkUVDC(V*y;#i3Xyl5c4=I7d-e#g+bIx{_a)=qM7^EW!9L9H4fu)h)j8`R!WGtlC28++bg>{IYtddA8sA-SP6 zp{NK(&vorvTbdCu)ipEYzIsH-EHj|2SB+sqT?K6}{cX<6{gSxyjcJO9(iAqTDr;3u zP?;&=_fz_IZIy7OlhV}dv{$IZbld;$uO?>aY~<%RY;MM0AGavixSo6fyfR;zABu#S zj`4VxW%%4$xlhM9R&+dwL~re0+NZBUXgzw6{|$zFKa@nM|?xF5~xu!wZYbgV2%2G!wx@^;!9O*qkK6%nfO)a$Uc4xi#>gmWPa<~MFc%+zrZMbGhI33<4N>0M}#?&l`7Kn-o zykqPba9CdCjVFSWEZ2M4=M(^p9}pNnxG~bqm_*O5zaPppsLuJ-;gRhxJAwc6Gr;g- z#O`MDM*9Y}51Yh~*U87z?3 zm&t#GD}f!rFY{bu=d*UF&LGpS@9eF777YMe`U>DN(gt-74^vVC5c$!Y2|ga#ZE@n> zT59L1Gf@2tCPE}x>FxN;wwZjLmZ_#Fm>(HyT%YM0UW|3(a{(rBDKdvU0-2iN;A>!1 zpkA|>rVSC6vEPac1H@*2pE|@}K+w&xh3z(-Zb8VE8*i>}|IOVeiGZzFus zW`WSb=#<=-vCj%@Q!VIy4f@J1&P>)y6MySc>=MeGmL;iXd1L%GQU&UA)r+|3wMXk7+Q2WmtE(WB3Cm{#pE3{k>RW;h z+@{_J4hge;_YZeXQI@^!q;$|5zeIF_gU<8YhcF>!?LZUeDA6L5BL@8a(ZQYF zXcus&6{9&e1NqIvA~=*fSF~se93#O3Nd4*Uuf__jm<1U!zrdNTk-_HNHaNz&I)$|` zYl9+)m(L+}e-pr%cx|0Md^{QC@y_bVqxM}ARlJk=^Hz}y1Qmh?~`l~EsnpYtt zcO?_kW)hWtP0}Ey{4}e1R%!1+i7%g^XpdHxi*Os+m7fnKUACWdQw&KxldEtRn4}{w zA~0_U#aDz`8_c4y5pX>5 zG)ABp>87siCwtI#u=&#jegSp6|0-sQq3yq(Y3q!P!ZyYptzFjReU`lhyhEw5O&T0! zxhoHO`DbrW-C9ik58p^*-NEIyvfiypscjM={QpOs_cB@M0|X?H&7jM6*wopOOiL?A z_CZ|Rx)ZwX?&1#ZdPH(*Pbk+FMmr63K0?&H}^U?*F+M4 zkca5}r3v&fIWM%^RFg%Fz@pBgdfh-^IKh0X}pAXX_J z`@f8{W5Hq<-q4hiXfA;*){vy1aRctYIy6{5??&gp=FKO=wEATJ=kt2WZu)F=o)VuB zMP;Fo``O=WE*aa7CJ1{H?mLt4y~3+7`fdMJt?w&VsJM9CZcfAX=nIj(0Po#1Iangs z-Vp3Cvk?qYUkndosA3S^>?A1QQl97LPTdOj9c~KG3>HI^)k`FG0r?c9qrXvWH^+87 zBs_b(c?wB6Z|xFZe>}Pvegf>VJ2k_$&XpZR34O=}Oojc@cxX{O7zB$|UCOnu7HnDnY+57-yk9K!ov^z%ZP)qxe zZZ}pthkA+d^jBC2U^H$L;^9K;c4nfPCM8^|`!CS`)* z6w@TjPq~rx%ck$$zS-wg+81X&Pc{I)lR5Ic#%pcfA#P1J??n9VZcA{%h=8hnnDKxw zLJ5eeUE@z)oNzOIrNhKSJ^{03`u}~Dlp6x$Tv-|q9M=K<4Xywc;0=-ri|}s?sB}UW zw%tUvjXSpNbp;8cjQcow+4AN~OEoHTHx#x~N#Gq1kEhJ9<`c01YExydPzXKQXSJPp z57F^LIdZK$9o*K5!5p#&iS;Gqy4-2Ivir~CVN*}c6S-$15@x8V$hh!{D8k4ZM7QE> z)eF~9!XMP8Tc*!V4Nz|>7fs2eKQeBr)fZ~an2t3C6$ByhAOh>#ziPza8MV+I)9MCB zOo9kp4clR_C(j8gT5fMOIhWYdzP;(9F+!EFf^2Vsz!VOzE* zgCfw+;8%IiV?-0Z4FsWZ#-y0>DE|lRg3eUqt^pcMWeK}}p`zsfXh`})e8T28{H75q zTfALmX6Y*zSkBwVp>mQnWr&ox=y=!@1u`kVvx9$iRPDmvGS7LcJaSrm_gh8B3h{b5 z^Px~$0z{EJfYl`@;LmMQme(6#~0L% z?{@}Y<~}5wX&LyiJNcRt7d?t9<&{yqP!W33mkj_W$t^*PV=Lo!xXt}Ly)V*$T%HNOUmpYKSH zQ|PgyK@yA<@UzJZq)Dt5%WteDK?2+E0diM0s(#O zUjq)1!G#2;4$54XapWebQVJsy;C#F^bk+RW@`en?CV6n^+pzGx#bi{0F0b?Sh3Hkb z#Nx6KXRmAw$h_ufYGi84t)V~MPWx7suni^GJ*WeybZk=v2Kg&j|CEadO()2V&Zgmv zCS31CZ+1>lm2iwp{qy|i(-Q0L>^cA`UKJ^_i;mBT?y$aC? zuZP}vngV{=LO#N^o=Lj>rbGSE@Do(xEqN86hB1gwm`z}0ivQd=&1VZ>7>lc+9)xQH zs_qsm&}iCOJn7kiX4QbmfY6b~`HAYb97k&;8&z`Bmt85V?DERfd8q^`fEjQkI(NlE zZ6P}?4W^Psa6Mt3OG!ES7AcsZhm-LwxdBB1PvO?E2Zw-wa`H{KPcp{`w)r@y2#CL4 zF+BLOxVC-3twB+qRJ$WGJz6#XWzK+)hW<(7MX_MhaY9oNgxb$v_oN?$4qr{8@q6WH z>5N36Bf3Cc;h-F0g-Z&TD|8*hedtM)qT^qU$HHmO8F6O9i5|3G4(kLjAK&SDbkd+TX-&GRsHlijaJ6mQO?sa< z5v^D1sJ#@a!&*>8eO_iy52x;+xX23~c?u zy6OiC)T2>xXu8;(7>jM4Fit-grq4pECIl@D7z|8(mypk-9I&E% zUo<4D5;6Pb+6$cXLZt2Gl|yNI42V}H+O@P{({N7d*jb9>wPa z$1`|AztYs4CHCS%23hI#?UM=Jmc0`5#ywnRFBucBp=I=6}ZahnSIQPn&X+^i`fYpk0rLIorqG?v=A@2Bz~YOKMvm zXm_Kx2`cLonDu{kJPI`?8!$7O2WUp9%Ab~6IYu7vvV2tL<9E=)gk#<*V^rbds>*=5 zqw%3yPI?h{^9?_ltN*Y7kh|&W80$@yg+^M%*|b&A=p^AUclnNnNO(`=R*MC&X35f3HJ;{Pzp?IjjDqIg0 z7s)+}XH}S;QygzXMIk02-ArAk2UmFl1;W-!?Sdq61)?G}iL%atcC@p(lto&VPTNSm zIMYVhJN{8&N0XG87Jz1&ZJK7=-_Bf36{A>+r_vFPWqamhE0p7y>JqpddhP2Ys=aUh zT6H{|esSJL;abwT{Y)G3pwg^iTP8FIjQ+M$wSQ5Nckzb>H4wv<4q_9Gas{Rp6QGFh);W-YXENH3a=T}4-uF~e$DQ_ zr^#+fx)Non2(FRhziK@|#1}PuXvmz&+<6QG!3P5hZRp{L8b3pSd%_|(BRr89ewXe( z^p~TilE}6*(446JA`R0%^q7bP*i&uM01g9LfWuOFtoM5TDFxDQ)zrp_9`f=yTafJ zjk|`qwLFXa7RNCaHcn7eWcrQFdwSoX5B|T|tQIlcPY3mFK z$;S$<4~PVxO*geI-t6U`*0T^1KI$*%V5RZv2N^qJ?>>fSF~H8@{@K&%j=mQD;g@34 zp+$tQ4!S1H|3xZvfWxKxoF0u~Vl%IphjyAzdXKjtDp6dPH@eCC?(dV%VImHa&`t1h_&Mg6`lz0cI@2jyu7`t>GOzNW$u3(UpeK^32>L^1JNO( zAuo^*pm$LudIbL*(cbik%bokg?uLNSSJLn;53}b0%e{!H_KNGq+hHwoIm@TyWjYnc z&QXYFG#T(NL}jgd+fkA;t0IKrZatd_Us+bS&{w=N9gm6qcp-@23d{;kXv^N_KOMHy z%<*rzz7oFDeN4*m?G5d>U;6+bB7QScXS(7Wpd)}E%~GmdZO=VbbfZb4ZdE3-V3Y6c zWEHI7xlHz)TzP*W2#r>y%`rGEnO{Q_fPtj+n?SP_ zz&4@tBfSQf28^wDE+z((9Eor@RQv5SZl{i&+&0_p>>BNx_$l2hLYs3nCTezZ}5M!jr&}3)NaT{`LKfnJ<0sGkl z!oK|5PP1MYlx}b|!rEXwZh#pnXk)|#oOYGsQ#0IjDOYNVDtR>L-=H;_P~s&pOULQE zU}Y{viQs$Oe4|MjlC+1h{FXvg$fx~a3@D@=J$V@~U8V0be3QjuG6!~|X*y7tTtCvr zc(2AuzP>NJ+rcOu5J>^`fBTcLQha2g=tx20FE88+0kCASkACpQW=!i|RHT?3CIR#H zgk!S$W71(#=~8Z##=3%tG^ChzHI{1b$>3KrbVh?!MYL&WOvNrir2|K-JUy?o0|I2j zzoIp=JTNmD-r)$X@UhV*^rAg3s$2^rn|*@crfJySpou3GsRnS-e|C<86)d2=o^8NJuSsKpc7ZmGy+f zfWERzp$d9rVA!F`hK`Su539oWv3h|JzUOZuX_GteWk*E9WS?_+m5*oJ4Qf@QBjy_|{Sjgi z%@k=*{L6F1w_F(h*ryp)%PC%^3ypv>x#tnQW^WW zrm}oe7S0o3r0hVc&Z^gJKlhm@r!MKlrEy`?Q^#i|;F-ZFgPkxFvuM)I`k5-6xQoMy2uNu zw-tAJ@Jje8pG{9NvHoM#zX~t4)2!<$MG6F*iA{T4)B8*MGx;gK z-Ck#4NV|AIM0=uxZ;i92TooU|mrnhdQ(ySVWI3&BO`pX$d(xa}hgon*`|&}O&8KY2 zJ8kS_y~J)h6P$_Y9>%L@AHn2kmTr?TBWR*=!N!RmuQ3+uH)eEKy*K{KlcOeTYpQ7= z7~l*OF&o8EmQM&@pkA;ls1V+|XxS0=Ybm}w?B(&GO-71y8ed7Y54c*LE~E6C zM{-mZ%t{jxaI4yFx!eFMOX5tz??&GIB+Z6qxQr0MgsaBF$C^_$Y4JwkN^m6{j(U!e z$n}iN?CtP)uQN)fYRQchKvy8D?nCD-$r^U05pdrjKD{RWB# z^8AGW1MqHz&zcv2f7_mh(ko~@iK`ps4DOI^L;+k&P+$epcyC(?YCeRM@g2LY^7csu zU?5d8*PRe0a^$yo1EyMcbZ4Zz z-w{i4*Iivk zNAUTG53Vb%brj0$oQ;S&+D~g+E5LuT%XX-(tsS9}lb7dCN6k0XpkBIYW>F5VdgnvZ7hW!C!|c~yF!Ewi-s8*C9z9J&h1nFPw?M=EE=O5h|5zLBoscRHa1Dy z+~K7E3H)0Fe!nRRk2-WE>p}9eqHFanxdc3Z*p{;9gA9vd1e-8CI%P2+a7?uzK#edJpR(xB{&n_k?R)+(H`UbCv=w3^v=4?wFfQwPBqx-zGmIBAE^OiuEz^s11q*(HG{~^U-E@$6y^2tbSur zngz6zaSd~^rnij_d7NP$ZvVDpFxhvnYkjV;E-qBn~a52G657_GS5GGCLV+{8~uOUvdm(J=> z`l*7@mTzxZuQvR0?@dxst3rNZnd!<%NC8g5&IDlv1+LGs z37$Y|&ObCuJQ^dA%Ugs?jCY_|%A=0Al6Iv+i<~3SY~wPDu8r?B2Usk5m!T+0gf5yJ zFy6HCSz^w>3iP5?Y!YMK{TrZ}D|DyT4t;_E0}so}h-yBo7*^Yb!Vay|$P>8}dBuRS z1`qQGChY730X+Kyus!zUzF!QNHU}dIoJ5dejk%-v)~h-~PDb)oI0kqL^|mI@+;j<% zgdgpLS@R?s$R?wgq0;%hCo3R`l*Hf#v3>mmzdgw1S&`zb=5UsSa(=iAl-kc;rx{^; z-DX25C~Gf}OWaRY*E)66F3}+U*s`(Qw4I^cQ9fk530dKJNw%j+t`2@hlR8RDo#)uO zo|@spa}}%CF6?)6*e0^#P#ocpY?Ajpa}V58rs9j-jnnxw(t6eKoY;?ll7ZlfA+2n3 z|MBwucSg;;JU3HGex&0}z{V(}$F-US}J_I-D zy%Uq>ldb%jr|6&jumQTtf2Cgj6YBSs>KPFFKdF~NO-mcym%G6lfupTU6CJn2OY;h6 zNLsYnPrbvLW62zi*V-Pms;C>1AuKM-x(er#@_| zT?@(`i6?zO?$bsU1)ARnQ~|{#3nU2afvSKAEAipe^^}vr&Wn+gYOSClX^k`noNafY zlz_hW(#0jMU%0#rK;69dtAYEk)RNf*uWM`JVK2jr8H34_ZeZ!1uVwH%>rNX4L@)Dx znbM${MH9)=zhHUF0uV`nnbHW`aZ<}&kPPba=deaww93X8o*8~6qTw)eS#;mMztBHW1EoItThJn&YlI?qx~vOCP5av$xU zCrKOh#rg@M@J5`LPa9z!f}QoR&}2sMCj-v&6BNdUghuO?W|VBsW4WII{1|2Jjg$^$ z8^!<~h5`$}UlJe;37dcH$1F&WrHO$(fhAsEnA;Mw{EY$u^vl`z4LrUgNVcfgm+Xo@ zWu+k*dfg0HvL1Qu@PZ>j?C#7V&Y3NE=gR1`o~|D3A38(nr&(drcW-|U_(V(X0PtPF zoEqSJ;|$?O>#H8PDhFMGAWSdLn3yrs7-7uU+WSISyp=#2Vvz{?5~6v1 z=SjI`Z(+t&Qw`q0`TKWifjNiEp;ZmL+y!15PI0=5I;*wbiS(Zeu48ft4be-8%g{4| zO~4&Olu&Wm_y)wu=1U9JUU+><*OE@nkg;f+9Hr6)UKtX?Ig$yF>dhDVmePDXg8T7}jXC~X za|K6oZ_#wf#{vlLqKGUn-ana!<8$xX-eu!l$tgjl_r{4HY73c!Dp=Aa5>DG(+Mr(( zLm=$V=0Hg2)sAn2isB(kY5L$-kZg%*S#Ii6Dsuj}m;mYmnU zwFzLog^vj*f=z_mHK4SsR+OK%dkrJxSS5JVw0$vwHXS05@Wh4bw@FFl5CcK8-%FV1 zcHm0@Ev#ZF*#GfT#FmnR-6liToTDK=RN0+sj6@EMX1ce@(G2e$E!zpfu7=L1N~XOb z7UVAU1X6vXfdTx8LHPvq1neDF-xg|*FC^YE!4iJK*6(GSCeEIY4Ox}u{S6e5@;h6O zr1+?vr*J*=8$ZIZ__wXoybP((45Xd#gCJ!13uI#GM#zsSDf!<<*QQK5TCBLNmty^m zsYc1sH5L#TArxmtPe#*jJvn8d$A#G%jQwG#ccc5Gfd*K z)t30$@7@bP$BV=X^jb&nrZj^Vt8~CnaN-HU7`Reg_-QcV2Y%acbD(mE&MF?mU?T#= zbdBA*C!;kY%=*XK zn=6_$*ihGZ(7J!&t_XvlHfeA%zwKovopc8HM2BcfYh4sJN!364feBb`0 zx4y5sBZ-qA^}XQ26=dG7NLjspjh&8G&@$ilfsk#w{eF;y7zA~Obpk9y2tp;l-7FZ- zI%e=+7)|&k;}6$0x|Re(;GMLx8woAhsI8CxEHby(2P2{UA#|Nr3YF(|8^47mIJUI` zMKwj)tKT|SpdP3Y=<5GE9{y)DJ$i_~K3!~A0bVVK9Cq{_AInrUV}p-NcN`UuKf8&e z2Cv#8^uj0rR-OaQNVqJL8X}A29b+J5JNXvCh8>tQAhw>1eNp9Ng6IQM%@Dl;^MU|{ zU(@jP^g{K%ZCm)7MfvrhOqS^%d{aeuyUY4VoJ1m7?)SzB1yt!=`P6{VzT98j)lAe!f+{PD8h#G+X zT#{ZJk(7gOmduX7S!P@Gx_f44f3njo`c}ZKXI5WvsKL}{qGTt>LXXBSXD5M=jS2|* zhyq@5rU#)T&|#f0r360VJ--b5Q@7C4ljxc!xmME>U=c)H8tT)UW7SyZPejcYbLXAFoR^xshRGkMs-48+(V6J1OX$Uw?RreS+~mFj z)rExs{YQV&bhezXKDN1cnDXYhW{`a;H|>{DxdU07EVk%iODR!IFP$v8@SW@whA+|| zUU0Li&wYeS3UF*HXFujAEseHX+7h zMxk|xEQ`Sa$yssf>TRxbYT@+XjM<)k7IAg~pyG373)8#y#XBVd6TSMwZcjTW{x7h9 zZ$5)~rychcKV=KdBExso?wXU0#y@6elSh6LwR)DBE$@4>vkU=BI7Y ztpjyz{aakj_9}+e5815({_Yx+@yP&Ph$sf`?R1~VnoU;yq&Qxwpb+>j1JK!!cuKo- z(rndzXI{P6otL@0Mq&lrM#dS@A_|~?^}|C{3Z&WFkc*0Kl46HX6a0LO0LDb!^%xCm z28cpTHk1ovQLl=E!gcxnZ0C`x)QDnXfCClc$gcs{yxwZB-Uh?W0(kVJ;BHDE~!(&PH3Q_*mapv8R z%tD1vI=+&Vo1cAW@Xx8OWtg3*Et+5tYpEEeQ=X`5qdb;OO7I9P7b`D1l`)MAs;rqZ zh>eW2?Wb(Q8+@-53`Q{8YOdeytH7QO<#tza1^Wx5@1UAD8pkB7W4k^~JZ&F2KskdpS5KbrVLf7AQVuYE4&0r-OTIglp#-(g$ zz$|TaHJ9XGDULP7)Bt%DjyP~^yA4ytEeZSGuxH-vF*?>jGSwwBs9GGfd`=iRZNJ`1GC(1wW#l57M^bW=zTrSeZLREDc#LWXdEmaOK=S=SAyy@Fg$ zL2)=Y=n%c++-8~Q4H+o^W&t*C%1hGr;lNN4rttalv_`Kpt>8vq<@72so@m6@R5G}; zL^7DaW9rsl%WO&Rw8G8NbgHSs!(#PD?JKd57hnoo+@%|iQ)8B^e^x9sxoKT5WZ?9F z&eNts96|@6C^@>DOYU})%i-V_a=1iKp!Aptqv5%j*P%w3q4aSAZB=K*)NX|D$*~7bdY}X(++j{q4HTX#VVB z0_aE7Q)*AOlkSn=GO=8PEXJH|Y=)FM9xLXIDzBkXrK8TS@y%GNI*o7ZGI$3r);^py zW==1Xs%Av*lRSMmXS1s&J?#byQpv{EVF^>Yu}@GE+nOZo^qoiifO`F@HM4qeH`ryL zN7b`h$8 zM+}QQHB_MfPdH4fQ79fX#6O+5%OuX5dCtPW??>JH=eL0x|Bb)E#cP2c%MnuEJDJ=* z#gy>@y%eP204A_(jZ7CehDGAQbz-dkFOze1D zv~}b-vNzpq08JpbAH7D-YI94E$S23 zt-u`cskY<+vTY4U*ao!MeL*sPzmYH62*SB1R-QKF3lcLYCYuF)Wi5yNq8t(DaN}dv zrDG*qhUWuM^Mv3Qo@~T#RDNXg*~Rm`$fYf1byLNTmMAO#9+--KMnfU2YH;#WS|@3E zsprvQe&MeSn~H(xH0WI_6S(gSDfdsK->xgVT5WjL%lwm)qqNw48c^S-zBUXQd|SSeurqtcD1zOM9-N1P6>rMC9eU6I(g!w+lUS z6((6^yzThOxmn#&xe21yg0uAGZ5WY_m3q+G^`9gz{KwB)jGjg1;+2tPKGT=WZhEJv zZ~cT$z{BbHt#Nvf`tG>z&!5-s_@dBWK*CG2&&O3>){=`lqOj ztI(%3W}J*(VUI#Rb!rv+ehv-g`rOPnH{=C_KKy=^-TR>DJ{zHw#Pv|>UsS$!x9DO?S$-|IQlU>`G^-e?WZxw>zoX|YPZ==N&UTmX5_DV{%3zc3v|*2W!5sTo zuMLRuvg&sA|MrJo7Jh4-GUe#ycuFHZO83I1ZA(?R4%|d^|77J-71!&G?2>uD z>b2(<+!HxKfK+bxs6rdtPaALCz@;x9^QfpmX+h6`aaQuf;iu(q#=DWJ^ToU{LOA@D zLEK4=2Mnp|%;2wOra7RQJakOB2YMPAN$3mc4)Yu_bi6Lm3x~<-5~khXHqu2fVM%-U zD?X*S+~sP>58-7+yd7IK_bg*t$gT5Z$GdnXMSNaNwxdGC z6TGIiKPyW)7b1q+awLEHZRF@rnssHK8s}usca4Cjby!^G<}ZK;9jcq*PY1h zX^5^lF5JLhd*PQQWGL>qDtjZCGY~ae-vm*5*#G4EeMjFkDd9OqgAtLQE6LR_iSW&w zY1PBa_W)0j_f6lXzoVnf1-Yu8U?L}#DAkF40lqlq@|ocU*yh~G#7sZXt+jH@?bj#i zgXO&OMIWJ+^%QOs(|#$+KOFRPUe#5QZX10vCz%KP(V|Hw`)z%oh-2Q*7iofjXg0+Z zXhRd0E2ish1B5&65;`mi>Sb2B%CqGq%6n`P%G2LItI6~QqK0&TW>8BrSoY*GY%tL4 z91#)=S)naXZ7xb&%C$d6%1B*GALD8jBnHS?UE=j}b4?Ht7XP(pI&Nb6Qx>qzVWD>HWAuutm)PCugqO8&!V{okyE4>YAr zu+!>m2)sgvb9Atm=y{*r;}TJj`L%fQTXCvmXUoENFN|4&&Lel5;=^N17rY3vT&1xv zT-5AT^fkvSP%jmNg^m*vzvXavL9YHxi5dCV^Af*wUVc(}JG{$Fv9aF3S^o%0Sw+bB zcWAOxWyIpKJusDbSLQj$(qmqa`&j}Y1M-ry&?@f+mAm_d+CGW0Zccb6xp_TA|NBbuX}>% zdJV|fw(+{E%MdQQ`6}?93f$;B9&7-NY?0j#LabTEWTf^Ah0g*~>>Gf{1Q>7_1R^3R zge5cBI#>Ci-BHnqP1v&~WKMt1&9loP-JH*Kb$YeaN}s7-~!IQ8n5$TMS1ewuB>yoqU;ci#6VAiRFz;1TPnfU-y+_(xCsNb5q&l?H%{qm z7B!odsPFHTCP#ULfVkvE=oFvZ%>B|z(6tdY8bogGATq-s@ZMHRVzhetKJo@)Vi;;_ zZ0z28PZ#Mj>tVO#8*kzg`poC|^ru=1GFu4VYDTpZ#a_pCJkr+KL*HuaTi=(ER`I4*j`d|*^FcY41iz@;@#5z3&Ln$7h=-! zo*^rzrhiu2hN2^t!t6A zbG;6-rP&G|?@T(KT3_ILc5$!hV7Bf5#X+#b)CfBuw#|O{dVI;_uEl;7iC*acxRSq8 zIVqIwhF>U@9U^2nrnPY3V!%zQ;@JifpyK9oe!EjLOX}y%kI}2JvNvv$iCxBYmm5QD zUr*deKJddnNeq(8me1F%d#v#fvsM9+$H(vpAnaK&gTWZ+IlP*ZywP?La_bcM zC!eF?9wpWX7Cks1>1dYO`Nrq;ZnIZ+sxkH5!MC(oyfg?&HXRd(;?CbA5&%y*UZ)N5 zbvF|(aH$?Ugh}P8`maFPNsS=qhFxDoJW-BjpH(X{fS4c8d)3{cxwTv zmh9Ag$?d?6J8emZ;Dtc*rGZ?&rm_~xls3a35&(PJJs7}`TGsw?sERGAyo9nVHc8@P z${sm``QqCK&8AS+Z0T(=fGZDyl<;d0%`Cv$XV7;BA@g_A_8bRiEdn~c zyymkyXwQ3B6dXk!y>xzVCC>Hji&u)DgmF-#BL zHRwlmATZnAS$AKR!jLZ|u57!2B4%!JgB?uXQqZpfKdJr(t|_rAEvs>G+f|@X!kjCL z%3cS_FPqu$-#c75;xuYQp=5(!jW2DNf#f`5Jn#5gKQi#yCB$_k!cR_~QHL8L zLwS213u_VxAd#aFpN!lv`1ff)SK)Z}fx<86tIXPgRA+;1@EWnt?cW%U3-{@d{;)5# zA86;yQDa_YvJCD)sXoh$KdBasDR}t&3PRUCU(~~5Ek(B4WTRV=F_Oet;@6K^Wg1~#zu~R|3>E>{AtPQ z-@f54Lt6!2Lig<8aj*Xx>HQC&>u&Y}NsFG+_X;se@jq9yn7kc(3#4+M^FZ^)MlP#Zk#JHK94AI=ed20iq>Yh z`Bm9g8hledILgg(cUGUMPd?|_uy8j^!hQ z7jG5VPX3(6**3%y^VagMRH2GtI4BReM!E)2MnkMes{z5fza#H#M3F<|i9NIusRnBF zYpqFOaq~mGVF+VTBX43k=FYkhJ`!IU^OJ7i3-JV>&i1Fk5bS_ckjO0i3%dk0K6r85 z7TmJ|$FLz^DymP3Apty>j)|Uhe3kOi<*za9$g%u)V!*!cE1WXd7r#tvle^8ZB+6%NU-v8_S_fI@E1?6hh3KN$%ss} zZam(!W4yG~*hPQw62K-)i%Rm9rtO)-l$LgEn{!~c*x(gY5{=J3C=`3f%lH62&hJYK zyNq`DWre8c(azC;8m_;fADO) z#m6mi?7)KW!o=dmZT0CRXzN>B|BV~m`R%CmQwGc%lLr;{jpQgke9DnA;+^y738w-s zwsDfacLt4vJDLI9k4jxyZTcJ1K9Y&$a~hE9G53g&gekqDc6|1nfc!r48J)iOX6&t8 z_V3f<`OEW;-Q-^A;dwDm_IOINed%)Ndi#3Ex9KEUQ8=XBG9{%1==ES%aBocFyFokY zhNbPCpp(mz6JrYX6G$0^X%dwiPwV^z?B|^Un*=&{ftcZ7Rx+6qHI0Mejy2oPX-$4A zezHNAnf;0~0pd17^oUQ@oiBOs0Mb~ht>vejk(re+0kE%)zl(3tZEC>&7et+4=()2t z=C!hB>5U(t23j7mX;5i6S`iUIjk4n|)h~{SFyJG$p9p~Bblh-H2<@3kz{fCR52pJ0 zhLuU_j~{uc0QblE4p$3TzSIk&?Muj|V zWx-8Thx5Ne)_xQWIS^+xBY(II`eX`EFWI?bqs;gM>O*jkH7B^6b0*j^F|C|?+1M%i z#fVvDa)M(!&8K0SNKw6-Z`a`$Ng_+H2YjU>+qN0;LiRfF`MJi> zp^zFMPJC1}r`F>4t`S+x=DdndQcmz_hQfZALI+Fi?xDf2NXQO2~xkD zY7N5RlH1=EnVxXx{>nKQV)9F!>rY#TKG?91{YJ{GiQ2Lp?OW?>^^v9Ux)Ay|@juvs z@U5F)Tpp~Ym&p?eB^(pi7tF+ttSAp;AA(qxG8rT#6ukLgEc<^XL{R>}ipr9`;DyK* z7s0*F61JE8}h;(F1Iv zGaOGC@7lwt+GCkH?&d&MeS3w;3og=SdN;HgB7fD**_UR*9)SBO4qd#-zp3-GIF3~8 z6kG#3k7&ko8q$3#u&~Y>lw(ip-0AG(l=KJXbH?Lm6XiGKE_I0fFHX|<$nI=u%kukG zF69)9V4~9P-PUtOiQEPW?p7QW_?gDf{~?bEpCxeF0nxpya5*(sz@Ij_c>WF`H5;gT z9nRWs_vY};hCVno+y#fsey^3Jx!a(WsVBRR3O6lE@ z!XH#U-Sm5l3|tI#v_IrfJT7W8U*ztp8b6W{vC8M~89n^^5r|$sTjZ4Xx@^hGBk;Xl zR?33o_t}C=Oqy|T5M4cS9XpvrNv*H9#oL#vD+F3kEoS?rN4s@cw!Bx^E~8IHR~&Jm z8 zH9eXC-+}?XN{6U+yGh+0YyOMHaBH3ffi{`w!cP^%%Xj$|CKMfSQTw@l{W1#U`_&^< z2SLb@gw3m}kp$t*t?;di%Th9IOUK`-K&`QTa>DuBy*v)5+dnFy4>(DrgAh9Tj=IiP z2*n@?z;n<`v|M;jH6R{ER{iiL{v)#(T(nsQ!6Rb=5<8eS6f&Cpu;8|aqkuk{+-W-$ zo+}MmPqC_QW%8+$1tNG5Z>+4G(|?FJ)H;ED+bBuwezB-N56=jGOq0T(kL92E3aQrP z)h!ga(^8q)An-nS;me*OIyXSL0Cd@TMGyt17vCOGN4>ekxoX8tRItOPO$LqQqGY7> zdIREA8B5Ioo+wj&XB^zy*)wzq2Mq*$1^4yc3qRCEo1pZy*}#-sk~MmrYy)wrRC`0G z4fy(c$=&W6sZCp{G*xxZhY(RtmZf6_YCezcP<_eLsL0K~b$yRsHelEnCrJsVN_3Qz z8nOWkpz?iLT|ZxuqvDXEt%2%DT+J5B-?%DLAkQT^7D+6C4pPsj$JnKe+vs5YH+- z>jlVh&PiiC|DAJE4jicF;8_ydZ^tdRve|W={Kiyf7!3A&9{s|KRsiTNOcD?Yq;c_x zY_2A?{eM)wWn7bC+XuX0bSV-_nuMfC*AxLox)G4k5+kK+fQTZY($XN(Flsamkd{z- z)TE|^(E~<|_vd{-&-=XZm-EB*^*XNOI{tC~kGiC-=QX?owXI@3PpD4mrk4RnZ@voX z6t|oP>Th1`D;;xamT~iKANpfO&kRsD8#@h^&E791B~)t?y^oYRVGj>0dbs8($&^SF zp^46jp`oOBt3Z#;EFS8a@JKgxJ%t5}P# zD>g^Do1>SBMQCEDB+2ylM;;bgPxjq6bmb-4bu(o)QR{&~FR0&(6dbB>sm3%gbWT)a z8p%UU@=1HT9-b03&qWF?BBzcVjDAV!3^q957Q*dR?E|UKSx*+1e^Ss0h7YnVGCzp{ z&C5ksj#Qt0@C|R+7MmgASkBJtFrApr6N|n6pFZ9FpF1%i`O#kWwTTM~U-3m$NA-!( zC5L7G+UScjjm{qZRn>SVDdowNkBy)3=Qj3=1Md1b)4+-9gxn6GC5|bPKidZH4}!f`5dIWyLPQ{Fj)1b;oED5~@*=O9-DDDseRAy+jjXve!7{?GA~OZVrn1)`KI9fHy;i(P}(sY(=YaFKX9Myyf(xtetV(RSqaSdYIOhr!?U8lHoKH z^n2J$nXQF|1{wqZxxH{pCY6^xwZ~353@SZpiYm+(uqy zq;@M3y6AH;Y_OVDX!T$j`yO8UIKHjFOeXflkxUThx@wAoNJ(a32(b4%n_0M~$zQ;j zui(;OkF~!=+yXNz`>_?MM*2q$q5EoMT6We1WsY`p2Z}d3uR86O4s-QxP;Hsc=~EQ$ zCk|3s0Xe7VO!n>pwp*j;)e^U=M4o7G`l_qF8yc(is{Ud{o!T z&v%!ZqY08n8&K3bX#*6djvJDwOpig|y@||+b@TBt40F=n7+T=vs;xpi%%_GEj#W-N zj;fXeO+);S4xb6Wb^?Pe)?LLRO;4^2jriP$4ekj}RZpT7i>=&B#2_uGMnsK?5L3!P zWbqCo7^yElYf0GF$+9QcAVAPFF7B|uQN0hs5Z1J3GC1v9u4&JlE_me zdM(-eSJihoW+0MJANm~cD;f#0hyiUH**^;Bc$CoOseGHcbJ!$Y}`8|IN>r?%8d&qGo$LA4$TWO3o^j2iZO9n zUWCOdn?t=-6F>CpMNnCAVdv%na%MYErZ1`E7T62dmOzzcHknqCEwux4Q)45fl_sRU zQnA|aNQgeDLW`0@j-?~o(AHhBc6CB)%!_}SH_EbHrM zE~h%&PNEwJh4M^g|MCy2R$c!))bsbrGSgzOZCUayTraDoii|%cNAL?7pL3<*d8br( zUfr@F@HT``p6IRGar5F&^!llmLmJlc(f!dF6`sY5RSZtCwVf1S3g~EGvA)=e+)Q0B z>OCq;Yp+te_&Y|OPVL#X%?3-y8|ZO;qzs@5sJ%57+t2)p66zB+3wRKeXmua^Q21SN zmHvGV`1}`=%SA9?x%ud*v9lo*+rt~zwX*hp6|T1XuB{SGtY+)8O@o8QR0rQ_UX?0` zxoij*WeEh?1utsKO{Q_jLKtIfp5}?}qh6Rly{I`X(gHS9=5pKr;M|<2wrNpA=^sJ5*2lA<>&Xfe7krrUVC0X?kW(hO^$em)^ ztetmMEWmf15=AOM`MYn(p&*A_a?!0XuBXRXNn^#o2vU^ML=}m%(q|heq55@ zRNPo3hyJ$l!Q`v6nx03Z>E5EvRL6L3YV2xRDEog6ok**8rt^7DXcEr;E14NtTF<%; zemtQ(7xsPa%4HT_*+EL!Jy8F@S{@91D1vhl-N`|499T;O_hS+ELbv$_7g z3f>ms+C5SqKYBi<@%2y93V*`#L=_3;!DQi{JfP)0I~^o2BdGluX(e-3WP2m&#=vlJ z$3^p2Md#nloL`Po61R?r)w*`91fv95T-^BXRy*PT^q`oT?z-gyu!GmPW@v&I*-FnF zbgTA8N?f_k}T=0r5A{ zL|lV+hvjM8m>Dn^zl5wCrD2s6I?qD+HVg?`;PxESWY8kvX0jgT+7!OPmNO`9{ZN~F zYbRjr*yIuv!emeSArI)H`ZDh6KE@&n=#t3JA za^;Ch$mP(53=S|Fr9T={a=c_N#FIl~aFKtiN??-WnG7&nwc%#M2bld^lkRykO7)f& z%L|uT_72Woo*`-@5`XTUm)#fj@M!ui1JO?Fz9;kOrb+F=Q05m@-#K-W>l*)5RNFTy zP+v`L0LMPSci=D06Ohi_#?1Ih8{hk`8sHpsj-AiHy8X9ywMY2*pf07XobSpKsYRa zyXza%iT2?8s-l~6m#rT?;sZByc#^H4=UN^DutXI9&gKVjY$_CYY%0_q zr3TQQQ&Obfl1)KR3=dHW3n&&kAkUC78PTutXo1TFzl7WZ^Ki!)z>*y~HGBSmh>+ctD zYtaJa75eL0>)X_QJB!KJSwKNKSVV_FGf}bf8Qb@FzE_L23A#DVw!R9(ceuVWR`_dm z-aYm*izw$7C?@pAFw2hV{z=-3!m&?kcc`&k$*He=53X7bjF`JnA}D|wsT9!Gd{upS z$P@vC%2U(ul8gMls2jYSC)n#-QascDK9Tqs zDIT7dJ#kj_m?q{lYm2C&kR0W|f8SUHT)(2QAEBc=#(=oXe@);P(9W4A6Yc5hTG+laB?k9j z@-;=*Hq;ekYHn+&T0Pr-c`Xesk%z4O)(B=4d&BL$vECawGo(GuWZ5mxK28gZRV)UI zRc_Q5$la8lK?pFwKXJ+#7{jJVZhP0NE1P?N1KnomG0cAT!3kCuVIuSf_&ebfkZtpJ z;{)XNc{^{^J**Vh@lN0_MVsn6mqWa_T$;o>*l5%yYSCx>Tla&5M9|VJG1V8~N0Y2kyZAaM!Tr$!q474GfLm}b7~})^CO1&V>BW9|HtBTP6#Dmj+E)s;^OUOrE{u0Q zW6*oT(N#w1y}2!;R{VEE%>HT7mupBKhr)0crgZL5??C5gY{P5wtQ7Q|uE#egSAkC< zt3Um|t$gvr9*E4T6uyjir#Lss@}nT)8g`JvXS!wPBnAlv3vUsor)sQP);fG6((IGp zEKc2mDCztn{2Q(hPaHc=vA-MZ>vNoaG0|7CQ;|FXU7r=J$zp^kpOr?4GU@IjLDKwo zYsy%ZPp7{%a5rd?CfE?-#)3=7*ci)&D!3Ku-?M075Fg9zsNi>7aPB%O&4$zpmmZGQ zBH{P=^w{rd+K0KD#3?B@fB9RToD^#35m?;dVUjI2CGBY3;&o9P&S=yD48GvO23K`5 zL6CgzXlrE+AQ%4SyutxD@)&w%0ku}1@i3F=q@nYTz@|?!myU4vwB(u`PvB3Rw|OTo zl2-2brv0axvk#Kc(X`lVx9476&laFpUJRRB^33)XtQdG*AAMcnRd5u8;dKfB59#@j z{R{}{i`c9V_B*>=;-mY+s{`3xHB4~1{GhlU$-aD%y*%}De`SW&4|o^S5#(;9$53XJ zS9KF<WTo~>t?Z^a6TldHTZF0}6bpI>C@y``5M9q2TFSNFh?p>5cL*ijxBj)Q z6sDLQxmoTsUsI?7`a;lzaELdl4j^w(Zs2)0C9n>uO0?^PC{)W0JqFLXUrGBMO}1SN zBF+leDBl9r3~RO&tCHvQex>#UL;x8pR{&`tm65vnE<|w2fKvuo4k6aLxvZh{3)xGg zqVXz>E92c^VdI}%r-Gv8A|79kGmBLQRbsR7a&O_LaV`%KRjE`3Y6(_Ti75K$JK~+V zBJPGcN4e=t<{MKDkBSMws&n&%5J8pAr|;Z)OAs)DCxh%-DxPz|w?26ArKG9;QFcBl(wa_53K#*S>aR2wjFVchU#$r2P-=t`*ZK1 z;&nkgfxHImrb`7ezqQ$3M=qj!BPTx@>WNY8Qsn+X5EgY=c{3d&C6&Zx;_#k(S8}$% z+qay)MoeJ)ZS5*N+pmXc8woq&4dIjIf22*KZ%E0iDmO3Lg#v$aGRw_d-8wCY z&<8AgZxT8(cp9;;Ays>%ZfZajxhwqm{D?(mFA02C9L?SvUo5w*tPU9&22+B&rHlBK{I;$}S?uo& z$p`SFiyA*?fQ_ULNs(>yj*eotd*l2g@N<@?qH$T{^zQ;GdHR;*=*LOK zlTqeQ2nLi2C&jg+0P6$$$x^IIZen~dtkWueD<>fsNWe7&1FI`N<+S(JP9uATd*8=h z)br$q76%F|h=!v3x545hDT(}Z)iam!4|%_#k_v1#~%GE05!s^sUc7jgncOJLWyu zRj8~1b4?Ua>H@yj^A5eVWtVGYHN=2-+YsyWsGnbV)163G4F^tIXQF<}r%qpU zU4_dAqaSM(+v5HY8-3n=wyQ;)#mz^eM$Q*a{%+hp8d+*IfA>;HuBMR^V>o9-uvKd> z_YSr`mM@TDK*NuKr);4^nx`DkgTj_52J`6|)s#QZ2)SbJ?7thMGvQ5Hxwx8wOSi3^ zjSyq|fyN+xc|gl=P?V^WfCfLe2}l@tItJeehVgk;6ygp>i1A^gP8c?XEVdfzv(*@+ zGxgd`#bVN`e@4FZB=$-PS^rEUJA8(yVHK|EN#PPwvA3ts&D%+`$SM8tpd)}Y;PcE` ztOhX#!`oCN?hUkDRqZW2?b&^+_aEYgtaqlGt-_nINreNX{>ziuu<$59XqE3gE5kJ+ z^21MAE-RESNn-Sn+o&dl(Edh&juxxinmFr8jW-k8{sgSodo@iXBoU)m4R4K;+B$)n z)BXXGcLAUmQZw)*h}}-psv)6IW{DZ??doGCC))@D)ro8+I_VqvVId`jTjxCE6nam5 zW21$4T@0sx4L`pRbet2_#MX0cWE@Xkad5y~F=WDLmdzNUK@+G3VSqT_N1k(0s33C_ zZnh{6OsrXa%g%cjzopGOW;PDC2E3iH5xOo@dPu}MA8)mFKwr+NPX7Q_RxW8V>k2!E z=iOU&a5FT1J{KdsVsQ3Z%ye({QLB#2)ki{47(zocKhEGSPhC1g|Jd=ma4KZNLmY*- za`}ftuJf#V*5=H;{J`JxP+FHeBC)H~teU+!EkrB{U^r&g;Q>RVQ)8 z>>^0N zf%`1fY02iLg7tRAJ=KMY)D*hR9k*j8{^xMPdAnP0w;GC=brhViAxF7yx&UtXu9<1O z`?ek6TB?7FmSWa3{C3@)Q%K@YjXrMu z@!b)fJlQkH!(hzom+;nw{GF-TsmN0im#r&$oG|uR&y}s)QQb4Jw1u`k5HrF|hYY*VGZbsOl63H4wpP5;M4SIP zcoH^yZdALrg%!ll*qK4k>V0H4YnDtE%Ty-G*m)5zXUl*6xMy4MBL9B|j(?4r=_jd6 z4|sk{5TRmn=0WJR_PKc}$Brn#REcstb5! zDqkQwg=;;FR0iEat0S1p)Ow!xVC(Ntb^sve_a@&U_}V*&s6>=ZCvjx-cDZG7QZ3oa z`~?rFFa~oZ z{fO3*GzPz-EhCZ{C3XLpzSk(7<=#^|#~EjtAsDl;=hv32jYg0I#j?0>6(MYLj;*IY zhU+=MP!SOO}jTK60e$F`oKaBFDt+7`R83FXxbIC3f1(Qtcz-*JlvWdK)d#G z%RWuOMnl$LedAUQtvJ%Vezbc0!n!dh;TZ+uHGB-p6D^E3BYedjhn*-9peE=f$uF<+ z+R%WP2oHg%h|Zv#IHyoXis`dGa}foRDdbCCEgI_b#Pv6CeJskxo;8rz#~OOuZ^MJF z0)rgvw6dh7r3*$jf_UThY0*3-ZXc8`r9zYT4ft)}LLP1|8@@D$^0P3#aytDH>uu#B zWGW?Bl{VGiD3t+ovN(HQUtXF1UhE>B{Be2(_?f7&Y}4KMO4%Cbs;ATNiJ#Xj^m*Vc zJA7VLP3%kuiZ?@hQ`3zXTFvP`&aGnlwW4&kgjR0bp+enjymeALT;*1*v*={(5z`Kx z9Wdk~A#6%8rjt4>&kX`p%+H2X6n@^bu@)V_!6(D#VM^Gq2xDOzxsXJALM`*er+=WW zmJZ~`+3z-dAC7Y}*#or$hm>^1@mNG_h=*)$o{aKpV(VM+n`y(NsF1iW2lA4S1Kp_ilJISm7}gMz5*YUc5dT@ zngfl+wlZg?r$OEZ)cc=b+@uS**I04$m5`vMwJ6rr&s{o|hPnd&IgvHROP~D~@}>kuGy3FRjIcnz4X>JwoVj}s<2L*^djN_KK0elywtdy=_NXxDTa_~GoN0ONi=pE5<8n_RH*k1`_R zEC9;ccqT&7q!hJBr|}s)%)UJp!<%ekR+ye?5LmLXIZ%Zcu=SEQ?mV< zy;656EJT*9n;;x!NZQDB2sSBpBJ)B$WF~8hN3&ub1o~S}fvAlSA3hK&?x`_LVw?=I z0oOWStbb6F*EH=3RJAN0HvIizKQ#Sd29cf)YGK(bez3d=?cJ2uH&K3mH$;b$ns0e( z?;2P_WG|mvRZ1k9Md7P3$7Fd(a6O5LnJ z=#;-~6&Sn3li`bLw4R`Nh&V~qhF2~cT!qiguW`CK2rYxDS_wrax#)F-&(DX~h5otC z%gEugF-h|X+l=hihGil%vTDr^ZKFTXvZkke^wk`v`CyN=>7d-k9HDTj488VzRg6Up zQKg*LyEmR@Bd#JSwjfWz@+@&w0o%j}T1i7}XPbK0Eq-%h9~h;I-cCe%vhB|6yYXM+ zTuQo~vHyZbIG}0~kG$p4OyXr+!S_u!w#jII^lhGyFgLOB2zepIdYSFD% zr}{HG^r+#2k9>r*Ce+it`6nA5PrCdys!;Ehe`?1aqWlJJ;#No4Qs^N=t+*SFlJ~VT z??TyQ=+HNWoc32Wtv)OspLv9J3RTqVKL4!<3g8b^xlLU4jBUOdtNE>({TfEQJq*>#+m`W z&2zY>wk!bTEta2&e}iAJ<6)8&eAKnk64mz9!_Oqwo$5S!&)%;We57Y&E zYF;x+lsi+Yys_BuE0Qe@CTxe^-aaMB28Ta?0)qt88XHKQ;>&eB*DR>LNds_?RxZ`JgI}`0zat%$$$p9geFW?8OKS$!`dB5 zZ%S##5MN5JM5vo#KskWtA(wrbVTBii#VXhJa6kSg5#H?=jA{~_TkDEzXKT}4W!#mJ zjDYJOg^au1!e9N?dTD^2(n-E<%!in#eFm;Gl2)&>nw~hIKj4YxcUY09k&Vd~)zpUC z&+7YQT|EbFo86%9+&I#cis_q#6v9#Km7g;}z|S0Z{d zhGpL8t==49Z*~Q`)W46Y^y!{^5b&^Aka)e@DH&~|?wEB|Cs+yLT3X4vd~W4QhFw@` zbH>^tO1u0Y2fQ`2fLZ{xE;hclNXNatkTga52;0dl9@kxZan{4`4%17 z0t_g6zzwx}gas~4;eg?1$EybCeIAJR)2!vY0*q$Dki9#dPTBZOmieIYnUL0ygG|g4 zquw&}C$j2~Th=IO*in9xL5&JgP?zqmSg7waX4%PQykSYe`}^4CabsAn^rSbxZuaLD zbHBOMMf}`EO$b`ISE2&h`at1W>R1kUrY##M#G~*Umxj^~+*pa9&Sz1d-&g24t*3Ab zXDIR$o=EX+AA1v|46U{8vVSi}h)EMaOK6A&pHO-6U5Px_~nbW_C@>vDKXE`;k zC%czEEnKR0E!cSS$dnx4RAeeSlbdp%^4RQf{HKcllgH64fn3ydf4aUaS+g=kgtk`) z7=@Qy+~h}22I#Fmil_Rgx{P~Zr%49cV$-C3o8~Z2MwlQXT#ptz?><(S@sC)(Z0YmK z`z2Z3{Ow}@`OEta1$;;Z7dmaBGo#a&iF%={`sPiNnUXqkVKSMJ=RbIN;UN8+ny}t` zqGN7_+W&e1GFmxy^V6TqeHqe)vWj1MdQ@xL))e};N(>UB6pXiTUHc=^WxYOnw-E{R z#PHWCZ+)%_U1HLE_xT}fzkqpVh!)=#S1~|5LSp@MLv6a^*NpjTz1a|9LOfiBdsl$3 z25Y}Is#Y`0TFRX|cXf_-7=ZjV!Dd{2@LS#8UJ%Lv(+AlNf5>jYm4T%v-p-W01UJ@? zQ?^mQft1-vDGkiGT|vr2Up6*T{sM-A`#@BxKzPHq85~#T?~w8t$sv8ZkE(ZDDpC0& z3oj|FOIN-r1H+0wI%XrbuEWUCD>|drx>xx+&eQbLi2BNIF?MH>IT=aQuz7;&Wg!=| z&))lr1sPc7Y-lbAj<`G*Q&}eeNzi>lLNw*$A$VH`(E(2Bu{FeYV0c99tP(iVhcsaP z!KF!c4KT2FrBCNeTepp1rOJh)n@@$6_X=J*+^=Y4Blc~u41`?mJ_*8FoL zEw-oY4LA4PzON^r9-f}QNap?E;r+<4dL(`X8L|<`vyTkAiUN`D*s8QsuT*hHp<|kXm zHDPc<`EDEF|1jJGu%LJPf{wlP`M577{F;?-AQww)EK9er9`hcuIV!TEg*w+xcl}8|RNN&PtG3@e=>SE@2)BNLk`4@nuas&`<=u>+w z*Hq_sptt;{%%&k>C^!eRag^5mD^Se@kM=y`#6Ri$#+YX97ieK+WvtkE3nkFul<_A| z{wE5sWN6T0$D*zE{v!2MnmH#7szCL}v^PLIPLI=Wq$<^C{*~Nm-I-%qS0$F`NaG%e z;`7e2Vn`MHA4A=@?MvBqp^?AgI%hqf22m)!yZeUMnAQyv$Wu0ih-)2Gm>9hSMnv_s zcAMoNk}DR1h>Ps5s+10HavARvQP`;_Mo~j_x$4jQ@u%_`Qt)4y{M~rP?zgBlQuG=o z0F+$hz`%muSR%FSOL{qEqDYDtBetf?a&&^FMKT+co1H#@^|=!G8*=IIy`K!zKa2JlHU96yGnEoA?8*(Qs^A2`Zl?M* zv@hADzdXjXjWXf9hxh#VkuG^qg~ih~U-nM!&S=%Oc&i2)4mAQN?QGTI_Z*qZ3{^PY z?!@tEv`es)@&~RqD95#$673p9ADMl;!nbH$qHLgbhvXgHTW-xp((|YIHEkag+`Dc{ zF$sG7$u-6IaVX+_NxYyK)>}vDcWA^NfNgS}>ij5&!b1r2&DR(^p=OB%6Y`)k4#$#y1J*tG`q0wT~vB3Ple zS^d+ZNRoM)&ko3j2^6~zc!T*oCuGBup*r(19p#x>D}o18P~PICI6Y)k6ZG`fA(EDL z&ISocUdZ=Uc@LTrb;g&;L#JK+_K*v9|4<1&6;JkEPQM?K?XMksuw?FB-Rtk(wn*KS zI2s2=Y3x(d1?i0H(2;fO|H=_1bJ!1G>ZLF9Dg~;wx)7XeqnBKZA>L_ei2^e_e~*&+ zRYcs%2hW}d>t8lBOaXdazhIGh%41Kc^2GM~*@6NC?<(6Z-&8h>m$bP#&p$bj4oP0H zn$ot={-xd?-ZCafg|tDQy*&Wna3(J-yx{9%Ug-uGm@C?v0iP>MtBouKL?xVWPPNTS z7yjV}c6^#oJ6`MS+t0vJwB4p%9_Z)Pw7wq%2Kk>k?gJ)@5smq~Q~ve-0^!d7sSMk6 ze;fc!dcQeimuvF7XHcWo(Rk30Z`A?iy=P%h?CTC<9*%IT4|CPV|EDcSh)m-?61 zP?`>s2os+ZMp+?|(AJg2laZ9-WP$fHu7L_8eSC>-!c0HFdNJ}fI6cSqWd55T06fx1 zomB3prxg(vLiy$iw<~KUbfr&yEgo`9q0ayYY6Mg4XTW_+=>(K3+JiaQB~*rUG&l9y z@Qtlj=1O=-dUG;2%N#`vLu174i?_;MPW4jIYcMSZL%AW|)IRP=bxR6pT575-O9&6! zL@ZT!+c)J3c2DgNmmdGq+2*4TrgL|N_=X2UunwEsY4S&^uHlZpVl1n*3WBvlV$lnSMz=fT%5P{W* z_ST`|(2c{t(w#_Vwx6>)2i(53LrW%$#|u7btiKNfAGzOSwhwbX4$MxY_-K0R_*rcY z=PSCo^hwqD#}klW+oQ}n7Qd;@NVjk1m+ANbvbW&7+yZhjSBIS;MbcLj_{=Pgby8V>E#bQ8o6XTpby_U&f*cwYjv| zzT?RT+_r;aZ16|!Q@?420`IEL<`0AugZ0wQ;g*hy{~k##%a%C)#6A+#4BGGObQK>K zYq=9ML(7_r=WS4#B!4_+bW!{_97Nqr zeUVG>P(I#yGbPOYzJ}RTCZWhv01C;j_W^vqTJ^wDU0FY(;n@}fvYB)#O%+Pu1ZQg`1gB@VgI$hi$_l!w${c*cd{ zZotVJ#_4K8a63rvG-f|_85vTh3&#BA6&Jbb_PF6kjHZ=ppq$>JBacTF96XQXWgSsn&aa8XcJhHD2NzDm))i>@6h4 zN{-duyvc;8`B-1saL~Qa0U0h0kS>vt)oyat6H|b}CrGw%8Lm)1-je)?kQX0M<2NoK zD{55^p;TzUCA zQwIiEkpJIIU1&B-i#a9lu!>>n+(BP?;-gfUKfz(2Sl{}S1c_bL5;lH7FI31CG+nY4KSC!z;v=?AHqtI|Ud7?kl>f3HTa~AVE zs58OT`Yb@I05F;%P0V7aCT2BD;{#<`s*e&eVlMyjT_Z33t5=4LIA$;#(5C{B?g`GMAKV;fyhU3)HT;fA9F!7%)zgE&5ei@NK3Fn4l&G z5DmTWJ_=rcJmM7mDv!Gp=tp?feh_Ij`@ln>*ku+(<;m^Zc^Prs;NOn30!EuSR4d$V zYN)NXWv+CnC`o={Sf(i)0W41jBB{-!WbG^{GtrYjZe|?~EEqiXb$+2l^>C9}N)E>y z1VUbo)A8kawq#i9s{i#Zr23$&mT`u4{CR@q%zYn*m=SM*5_mTK9S3uxg7HDbFz6kW zXcR6_B_3;tQ|BI8{ZN}M`yvP~u#?_O4&xYz=@s4Fc6kN%T&AuMn)G_Mo8I}%*ac<1 zai}exCA2d8*(7ybuJRpjgRNjol#>+Wa6cj2??g+1=@xM%SeFa1_MF5uZk@Vj0HkVS z)f#E*{?7gCw1erq-_H+Tsp|A-C%pn|*&im|#2Agtsfm)NHwh)OvW?I3Ceh7m!g^r) zfFyQV;XFu`6Gd3@S5VH+<->vw76D~cXkak@uLqN_7!k9u5Qodi_>0oXsE6lO!%OZ&RP=#t-n<(%vAEjcI86*NyX0m$L)Fnn}I9ugnYCvF0V@c ziJg|5>2ir_G?R(>!Vcp^jk?XJj(*Byzl(g?@3Xeu(CZ@*`Y&9BqsT)bEThmyO)Pdf zqS8kogdueBC+86Cp77^{N&34$snF)r#p} z`N75wjsLL<_oy(wh9GfIA6Sf!d68B2JN|Pgq~xNoFXo>iOs~IRUZv!qP+o;AhiQ_u zXCtf9v5j#Oq}pX5kW@|z{DvzVXNV)%pz70|p1+;LbO!`tb!(|r;8apig7i(B4Kf3g zCab4g7M7Kg4`>7=N4`ckzp=10@ZXo;U-x760-59tMztW39C@M#{RP{Q*!BzV&MEh1 zLMq~=lTJ3XaE|kb+FAz%s3DZouRBB~zS|_%Pylfg5ih}D)^`-BKGM?a`c&(>d1`H4 zJ3x=SMZ1g<-0O3xnD5A63YL0+eOTdZ9Om|A)gS8APBp48mgnLg!|_I~4$ZOtgHzWK zlnr>?Kgi53uyu|$?_lG5{qm^WxiH&T^XX>G^%Aw5jR=<+tWr1?vy4E$P7ChUww~PN z@+TkGbrdVQ^khR}h~}LCZHafy`wgk#CtIzNimbmvQjcZ?qTfpr=rZGpvL{wHqpny9 z*i~vmTgN%0XRHDDzH_vHI=e>OVBr~=sZ%AD2D``)K)PkE``;Bo%4~J~?y+Hj-`(Tz z8`n~%ws?j0h(XukWlrn3UysqXiBEh>`zBApM$dLFXEEDVSAoP$fUSlc+F^W5y=3() zDyj->8@p%lxW5AoS`xF?(=(>3f*q~5%lAp7h+DHrQ)c;n8vo%xh_%_kq@;ir?jJ)u z=jpcIr7OPn#qlGbs+)1^3XbHs<^6C5pX^oBGrG(C1%?6F zU?;yqWT2xWwSv?Awum;HGcD@`qj~Prx0p1~lZ!y_!`hIxzh`;MK1aCOO+49Zv9sbJ zQ@*o#IrO3>-1K)I-{j2Mv3B*iWW-|LLj!$fFo3p6R{3 zgcx6CJsdb@Hw2akU;}iJrmsLei8%ZiQ=v+am8e|HFZX~83(Tk6X%uhhj4MhQn1zy) z<=u6Ls%Afq;!Vz9fEj6#Aod8Kw`h}#Z@*Z_9rEUkOHUWSc(00zR8lb8H4p5R`|71y zhc1@SJ1HM$0G<}>F3cooLb8^D8Z3O^-VMmuiPHFc2S58WF8qrj4i`rYKJcGeHqQwc zldY8Oe(C+`w?T%1uAih03@%c=!9;_(AwR^&bILsGaV?_vtaTxR!9gT;J^#TB-U7`t zUt5+$%zKrP)o4)nSu$-FBvARip;kV+ZEdO7Kn_-$nwgpLVWG)cO*^BM$}`<*=xs`a zO;f(u7>%o{xhn;a!%A?fRPr*9fJaoJAD^qMi$z!=`dcnQp_sLQfqc<*{B|or|1&t= zkaT1B`tZslD+XJ0l|+hp6MFFDh@U3i>K!)86BnX?t_${tU-s~F)E`6VRF~=1T6Us# zqx7Ra1$rHT4E6myL6*$2TY0TlWw-Jm5&SrcC=$zV_7#ep7awmm-H&i$bNWijJlO=@nr1EbW|FJn1hA0x}uTJ`NS&D|ST$HK$m1!&&(y#j9`|qEw zxd0c3=Z;%mSkf+r!m7yzzcWonq07kNX@4`Z`Js$;WW=zz%2YEZU_A z`KJ5c5fSKzdB4xkZP7N$VA_37^!-??FG5(|nD-$uki+io$S#Rp7PIFs%_~>et54UD ziWEApEoUo|*ZqhorkpOCr8JheVnl~vqp#TQCEF?q{CrO&=w!8IY250$4|UvpyqpDx zz|d@}GM5NMwGbyXWxWwKO@(IFb9?7<_gE6H%mwJE{-OF9T>&erslY&QRls(D*TD=NrVmwv)g z{u=6(AU*V=7b9f(XfY>Tc5-r!H-TvW{;%S2=q+DU!nQLhurkvO%#@uu7wb9ym@a`1 z29g$}lE_G5t)0;(W%J96BshoLuC@dQ3q((lWsUv_(TDP-Ok^C8z7MVvz`W#faAJ%c z4))}x;;TZhWP%B2A~=G0gYJ*SBW$U&AOhmgPZ0_Hm&CE63kbNO@M=!gjw%}#;0W)q zx>zqp)j3T|y|*pORt_Cv;n4$@lfP#U(zR+m89zeZraGkF`Zn=b1>>yG!sD0dj*2SA z%k;N>ut=fXWu@S$@$Q?xKEE;0&*`#U^{03A`q>6W2l{1i!unWIL1WZ!y=^~E9H2v> zOO;fd=OGM_|7y}pD*CTH*elp2L=WIwSSxtrC6lmxpEVCXhB7@{gTHIP_17HS^ zzF3Dkv>u=A0dk9X6qc%*R`$(!W;ujR;WK{Yqat)6hfW9iS1D!H$@=IzJPXMmf-M_8@l=z+ z=-V`lDu0!VD0cR=%6em~5-@!{6%kxv8y_bmo$?(;CH>VgQx)j~NUNc7s3gN_ltKD} zGJC`8fs|#na(TP}?sZf|DQh>)AtHEgyLqv`al>awJuqh7o3rR@@-q-Hz>xIKiLdxT z4jfnc%CD^?YExs>j&EJOL;r;~+lg)K`q6yHN&w%MoE}BYgQoj$GWn43{3%D!?D;3o z04{}BU06K|Cmq6QxNzl8F_Wz^;Z(ue zr)01}Y1(I7vw<)b4EKJv8}duY8~;9%{aq`s->AtJ<79`z>_dg(9bjPaYR0iZz;Vh% zqv`^p^Hx2;-Ys*-W0QVaTY&zz+VAIbJsZ~%bZdlgiKHIdHHom|a66pwMu7AoL$nxS zD0rnR+&9Mv_bhQL&;VXsHSE$>y7%qB@ZhA6=buIN&IHl&|F#kSZ-RpnMaPv}o)-;c z+j0nN0lGi)oma|?e4A!(@gWW(c~A0>R#nJjl_itm2vu(|XMjA_eABxOAN-BHXh_9N zrmaF%ws&8y4a3ky*RrkJIrAQ_m5qL)g*_f=5o4{GszVHv`W-7-yLawmOrJ5dR;~MC zPUj>Ewa>)}%>fLwb3$bX=zO1<8^TmuQ!R5H`ISBxkks6R*!7~K^^=5|w-^*1&trEB z)nfST?w7a)-%ysfoF*XVB0k@#pd70n!+9w9t;jQn_KL0oD^=n^X_PXje77F?-b%^&{WJ&!YJp#YRcakg<5L-To}jm3nL0eycD9itds}bXE-Ss)!T` zYDDe;24WfJ2OQouzhSruY@+-<>p5@mrRk3S=su{4 zr==Ici~v+c@$e8!8@HOVwVzTaEZ#(pT1smO*z z!3h<|(8V8fnW>|nHfLy;f22 zsx1)!Y#-A|2H;p)j__@tTzF^L>Zbin+q~ab%f;y+(dMgtpxmG720(@a(828xtyBKS=*{uWaqgFQ+pPCy2JCsdNerLfX@@>lCg8VKcZ_qt$ zXiA&X9LU=j@mqwE!IeN)S3BfOR16;TQEI9>()(0<;}+$ww-3zM--n>Bu4KDd%7Z(# ziIv9F0`DsiM;_c5FIb|ix`C$py20I?*i(jq%A4^z@O65YL>6@y@tnE?0&L#wGkmK$ zpVqU28WFA%?=c=Sq(u7-b1)8%-2s9(W+_>yf^@L?7frvt_SIBjGh^$E9*vj3;RL$y zJ%|Tk^E$6BC~BUD?iFRYvDoR)CX8dixKyJl|9Rc=ZBhAR^S&dN;e+$R0v>HdsbILYCbMR_|TQ>L*FL%l@w%BsL$Q^Bi zuEcsFtdiU6C3p0rT&;jLLcT3dO@69l2mJ_pzb|tdxx}K;J~jxD zSoq#=wZ}>ILq5FXpkF?`Eq#o)Jly26f*iQ_^8X?0tiziA{=dJVBnC(+tw^V$)JPFg zKp5R6(u|bRFi=4S2`QBp=^8Z}hDalzG@~ROHPTUIa9@7DasPhz{m;41`|oqE_c`bJ zdOV-6#fb}ZqBA~+-t)2!Bv-ht6G*y z*fZH}B>Btg&rfoxnKM6LkLpGVup-HNp3dlmTTWgfBUgArl?_~0CT!@TW#|5I0B^}o zn$!=^BevIXcR9kHwI`dCLC-O2c2yH)!$r-a-a{`4HDbFJGBVeCARmv>R_L4leuk|5 zptnM9=6b3IlSLm^`)~SpaR(U*YX?zGwkHXi)%*n1P>hrhPR0k)*fgdVzQBNG&SGxn;9dEPtoB8iv`SVtS!i9ybQ28wn{6Uke;galD;S)e1 zMJYwl>JnFd;&3BBvcRhL?S#w13a3PG%ce|v{nzPSb_Uuy?$Yv#Ss5y}@(0xw2e)_| zeoi^+KsU&eKOUzqmIgeqf~(EXW^UK?laqcWgci?-oo82Vg$h)>tuL)4Lx=m99!D<g}e~2-#A_Az{-EJS13?rM+uR>pBEpO?C1B4D1@J<`rOzNEWA~@Y`EXF*l145 zKT2Tdp)lyv^a(|QPNE}0a;Z5Jm!+3V>?C?8|CK5d@hGJz+`X8}kiA13>Y{2_98Oca zApIW}0BW`Bo`OQQ_eqL2QnjwV1g?`c=I6YpPvvYwngUQ233P8{$s%!IjJ}^&mwZ_} z1@nYPgdB%NK$&C9ob?)n#Uq|M^4kd~`l!qNkUkR!+;jR7VCfd#(uU7$DCVwCdzhzl zs!xn|Geb;Ll$rr)Hpz_^;vBQQ%uY?!Z*Pt9VrnX43}0!7n_p{$r!$FA_Ie|iUo?Um;#0p>_V=TMi!~+ZohoPkqGTrnQ8LLs%1k#R{0@YTkdejwMQw*zK2{4 z^5tm4hnq1Hwwu7Z`MkDZC860rDO<6@8NQnBa}WpDLHJsLE)^%z+EEt6y^HPa!2;N) zJF4y1WRYyzo&(pUd{DY&u)Mgu<_X_yS`_o-uXyv{7U-y83;9n>LWkC0JvJNbT5lR} zdlIu2!vdhS!HCsR!dBzuSSkjX?mFUmMM>fsC$E`Z0La~?b3U*F_ZVnz)Pc0M0fz}X zvOL+b<2`t}B)Rp*zvg18d_Gt{rKuQx&;Eu{E7C?RgD$k%6GAm~9K5@mxiUk&Sb6Sf zpw{5!scMhzB+fy69k#RI_zH#V@4e4&NPk6fr3E)_O~QaIXlU&uRZ6$InlFNwN4!cS zCP@9wDj%oDjw34f8~(~uf6p)bKkdDLZC`=D2dPmeIktgJCCmEz>uiz0u)mk-;&2#I z?LVA~>N{`(PR^U;mjXT!04^B;rcP%}Kg1c3{v>S{Nk>_Dwf?HWzZK0H?@!G8fmYpN zrZ&fTnKpkm%li0{M$VZaju|;M56UH5Bg~$;Suz$6a-z_V$_!?io`SlWE`y*JtMD(M zWGd1ZkB%D933F#Za#7B@IUY0yEfQ3opyob83x6(D6rgwylvXjS#D)s+@sURgX_=*9 zVq>-8aJaZp?Um~rFvF;nkW%&ghRk09PbOczXIgTJeyhMt_@cft5~LoA1`mT0Pve@w zCP91G0f8UNOeH!+^u*}nCJs^<bzmAE2wa9=A%Y4Hk1BXbW1MuQuXGOXd1*N*2$$*sDKm+uv z({6NA{ldb2WdPc`q?>2l2m91j4XZj5EHh0{RlW;ov8NNiw|9$r5fTQbcE7$PiCCF_ zcsTb}ch;YZQB&upx3Y^zDzG|logDM9a$#u9{UoHlL&a_e(0x4kE0(V1D-VfNRc9Z# z*%Yp3)t(UE@70BypG zX=Z$$^{yy)_HE<8jPu`OPx;^T>)%MoX6Oz7nE+kfdbdoFN-kg82=EF)o_K2z0Eqlp zTXX1WiB#i#3efKyT0F04s7r`gUh!#**j(L5*VN59{mFo(fU?Nt^%?y}L_CT^%%^)w zxAW7|8olqhlrIgmxM?hYvtSnSAvH2ddF^JP)-hAX8 zooeM~B|%>XAiG72-N>GjWuASzMyBPmoeOPrgsR%9l$+4W%@~h`x+O09b^iPtHPo!=a&syRJZ4en{=;u4g|9)O7zSy#-`4A% zaSqg-nGk%%oP(ADpKLgQ_Q{#@es@d!?9e+J3_qBZ1wj zOMotbeR=*N{hB1N{B~)HnabtQ7T7q=x7qej!w)!IJAO*59&t8>5t{r?ELd~`IwhL9 z%+$Ec))6?96HtgN6#_oT^_Re|edJ2C z?=%$q3{1Bdg|oP>ewpY9TdHoy1(=$xiamtrDpwC&&y96iw zy%N{nRgTRo=2xp?jBhW!Luu?-Mw$$GzN*3pgKv#|*Wg-?k4n=Jjw_W%in9*AH~B1- zond)R$Of1T=-SBklJ!U+C`|1(gNd(`I#E-*nGGKeuRWs4t!=xVJD$t=h+36A8?yN$ zPi)H~74H*en?~6V9zG_ka>$y6RDXx#jsX28-udN9D93=9vGF&H1{88PeTpuCzDeB= zxoBhQyd!^3KjTm=VreuU9?s8922PvMtCa^NCd=7N3(Q#izthUN6D?kU;aF*>3?6`n z&oQ8zQ%B;UMMcq$~`r|xZfRn=bEFJa?$tNg|c>F#3}dGPG98wuiH14 zk4d2piMF!Ln3Vc1t7VObxQoa;atiB9Z7f}NkxvEsI7)wAge}dj|7_=C&3KDGxCNG7 zcu^ja#WQhgpJh9K+MOR7u7A80Ysy?DWTW5ud3b~~vMNH6QwZrNpraJ>P^UX@8Ai%I zdhy?&#D5zyy%WHT((l11`3-X>xKsbE!w=Rt;El_j_mhR2`Az15Zjjf-*Zg2y1K{UD7++ju=#mz;^18W0(M6I?fN6hZ|^8@kZd~96{FjNtz@A52M>ef zS^o@+*q}cmy7MuJTq8Wv-(YJl)na162?v!aC%cueAaIF_EQyrzkv<=L#2@=>MDtTCMaNQg3 z=s(Wrg3W8rd-}CIuiFQ0co}TRpGEDQEv&+u?&!hg*|=ctt_WUZ3O!V=s4o%qf2#B+ z_2sN<(YslNDfp5u_wvk90ravaY>!@Q3AfvLKw+syi`wy%*w7wN(sg`OnFBil`KvRQPvXoMx&Ex70wCDmsDPtque|+s zs25-E>Z=6nJ)c#s&c*puu3Y|7zAz;k6O}&fmz`-7(l;gj=WYL90Tzo_Ffib@AEEQr z@DiT9|H&q?m7)B^D58W^@VDk4YFP9?9x?3nl9MZ)gehg`58x9MbJZz=uJx``+Ehc- z6O{vXNjH@v2bJ3}qQY)zo&?~h7OYEYiTQa#gsSj%jI-m2hep|k#cB+T%Y!Eh(xAtY ziRd&mzOu83sqVe$$;o~QRy1ObrRKd2olv8QQ0Us4sY{p%M=dFf3pcTLj8Vg|+xgj+ zT20amJroZ;8Y)5G3~}c!)(X0XeAaR$Zw!4M#NlD|ZIm8G%j_RGP6I>YZF>V`o_-B3XP{_guLNrv zuEqI&JQnks)+GX+^nEQK54xi@+7}cxhR-o`umR5DawzlA{QHlM2U(qx*n6*U#RK+` zIX)lukHBglB9k+Y99+o<^N?3zYA*uSiGyyx2>) zC^lWWk-2NQ00Rf`OYK%8dfM4FydTv?ep3xwmqAaWJL0n!Zum}12RQmqI~_{oRxaJ$ zv{7DfigXy+5Lv9Q{QYjtArG=dJS#sV+Y9|4V_8)$W3Tp)+gB)GnD-2U;e1u=wFcXKeV#RORo3(-noGA zP8zHxIg(Pkh5qqrSu3BsD*gTm(JTDS8EbpVF|vj3HQ@sZfPW^{27I=>pC8XGReOgy zS9H*Ymm6c6^F%~Y3?}(&x2NZ!s(J30iDnA)>K{iAbd1bPu*pK$aXNO;_OJ$B+s0%v zWVuy_FBPq#&cKm(j`&3OXW{XUZ1;6-nKR1;E8c)D+^-KbHU~dsIC+HBJ{ShAz;+=M zO)J42Y>5g7%OI}$1tXDscHNAPmzYr5iq__0_l5@aQzGUOK-?SQ0;PM<1Ht-ezk*|0 zky8W0bN0MatS$-#9a-FbPw&af^57%S(wiN^hGed0#%rhI?|lA=Xkids{_a~6kC3pz z2K(_P1?oJ#q)jKA1Fu3GKYI{~fO*!*AHOpN3Z?_c5NPs-RR3ZV@bj{c2f8j@zlMn0 z$I%mY`gQdFn?Z>cxh4@XYjxpR_J;JS)AtR;m%z0M6P`JhYZh^1@jS#6I6i(P+{x|+ zDX}NNebFYD>Y+WyfURZ^diqRncY`mB(dAHZuh*> znLKW7nZtN_k`*u|A2lW-&+`81)T0 ztw}Rr0jCAjFZ&skE{uf!*28+WZu9^~u^AljfRI{i|88UWlcp&BIg9>Stw}@=kWar6 zK`76=DPn6>Hq1{Gn)yRoHd4Cbw(Rwv7PBUO(W4~>55wHGar-ciTF7{jBG}BFKJk+o zunw4;(s?vQQH1dcA5oZ@6rx4MKNGcxY)-i@*UYxh;6biCGNj>wYIJIXcfb2!5P_RB z&Yp#d?UI*6q~3unv0p`I7(O)TRkp$483T)P5mDAJ&V{?yAzrR6Mz84eq^Ru=1oHc` zOlGVef)TzDj$CP0Ly59P{RbQ;($&bt_b)#AgO}g1EzW4o;cF`&1I8>UwzkOjf7mid zEF%W-Jn$UiR~*j*=`*s43o&*KUF}Ym_q)bt(%}ExbS*y9yWs0}5uF^`G$@RKAnB%4 z_8tdCY>5_!(hu&J^;~*o?sxptCg=z^n?pZFFeFTER!!J;RPV4oC--i=GUFzsn?|H9 zOv-=~!v40@!t?wMwKV%%)0<864ZLIY@0y-}xcBWGo|mALLXO!(L!i~l6d->5gftz$ z=vO<2=kM4nJ%W#%#AoME$b4^U0d#+Cl)}e=DQM2~K6jt7Q4Ki*9@%Z6 zc_p?05OyhQ3hnvFl?$*mYDCSBSqHc5;sGU|Yd2U^b?{w%tpSX?E?+aAf|u-Ez$)wO zu-V`j@w-9KkH6UQ%ibPk?!Ju$s)9|Nog-&dn-g84-NwA9w9IlF2AA~t@X_!=k5uW% z*9r(0@!VN|>Gd_Q@vqZsfarm%Em##zh&fW6;X?(v+R$9T$!~?;YCn#c`uYJ(NbV-H zw`CRGYx2qh3W~~@0aN@7g^wR{TPehxJ@lQJYW+*f@|-%kn2z7|4>OvIN$5M77OWb-uq1j}+fES(-JxODq{BVJ2n{plMRK>|`uHJ9 z;{HyAzQL|!>!Y$jBgKaj&F<&L`zuiya(@>awxXWpJn`3?;-CVtD&oX=F#>eSz40;i zJj&U`U#aP~3pNMZRi36+r?+wh5%>6(d>&5rmSmIn0EvKjRefHrO(Wi1<4!ac#WL^| zkc1p%(xMv~Fp@JzkEc z=SBD7pMsuIvVOG)mrbd~Ibf&Nu+-Nz#B%j{joqFB8uE4-%nAt><7%ow!ER{WNLE}8 zNIowD>6uoLJ$x_jt67AQy@Nm3c^<`1(0lkVkHAN3fDzR>R5s+EpNl@ctD=#~l2;V_ zRsrPEWy9_$?HzEFSH?#pX$WVcw%Zfz($Ke97BMXZuCG|1IJWQiKyjFi>$9qFh(QTY zq(%Z-_4aa3-|K6QvDWbr`dYin`6D>o;FF7LL5qDD-wgD-X#(LeY+7)uGuTzVyoWFS zu6&%ath!6r;c@$}68_JObiy>@``)B^#61SSbrQ+mTXo@OXV=Q>yDL{ASedi^xhi)e z%jIT70_oHmA5gzI5pGJf{+AZB=N}K&3*KzVIwm*Eu^)qHZ-#aAIXyRuc%1?H%V5HY z>VHpUC(n$(&+>m@%r0qet6V_)D^AQrMA@ZsJLwqPPWW`R8-C#k_i^n;L8yw{eGYI> zyWM$Te;qR!%IjfaATI}P6c!d`Ci~k_mRogTz5{|O^IYzwkeeuIN}&7m?(qwH7i-c< zFP>I5G+27I7%!pflaIN)G}F?TWutq9nuj&H?J<7JW;ra4;%NmsMs|jXpQ=me$~WAL z6`|V{lQU`4i0`3nO>d1aPEWg$-Kwwwo;_pi$5d+B18!|snzh4YGYxut{ERXxv8cY?=fp+IkuO0c;5 zj0fczTZeWb=UYOb(>nm110owY^?Ua0+G(=k@kAP#W3`%NNZ)n)`jXkPsvuE zLQd&nzd}xE=!l@`1 z{~H(9zP}gAjJcOR6?hRCkDEggcXrQ*k7zD;QlpyufU8J&boc;4^qxoQ{TPO8*JuOp zHS+VI@`~&?b}D_xv(v+Bk^HhCln%uX`K<|zhQ$OR4%8-OmBkj&45#`%|0gYDmMa3G zDdeEX+0kN+*eK8!z=64G)}&y*27{KQ*v;u6kFG-V4)w=_U@B@_y3{*Y=d<(Es-^KI z!W`6Cb0x66bngzZBQ+|>C8TW%UnB^c1-&t>cI$H$-GD_rze1(8Q1SfS)-)%T!R1Y?!0= zo8+P5*u#)-hFkZIx9^{*(T?3w;6)8+guU^ZwT0rUd_e)oVRVVZ>Wz3sjEG-d6F&6? z$8qq>)P`I_-BNu;uW;{!2=0WVLTmj`BUhLWBQ~#WFR10klM{w*La;62+F^<3<1xE| zFx;WPl40+q!i7q9@8xF1UtN5H^im+HzIGQvm4Wp9{g2|*b z2o3-JJd<-L7eGOtTH+QEpMi{N;!aU@Mvonsb z;gGx3lLQ7>7I-9nKN7P24UMm{$5qUAjlUsOmpdS@TKG?$>7PVLrPu#CU_a!ydPvd^ zN|};l{<#87tvIOv8LYku7ei&~1&f|#;d{uBCm?>S3X|wSW&h0wA-I+Z=t{hTPwJzX@cCBNcq2Is3g~ z!3H1r2)m!uETOH6u0sixS7s@6cRBx3x$*Za&8{lVv29Gi&TLi$y(tp#WJA zeXue$n{d9Q;vspSbonFE0BaYr4+@nPD02cDViRe-K)E$pneVxt$HWW4Ph;*(ZJOhX z_+`bl3~jJGjh6C7T6KdkWUQd>!juh3w92JOF9+fhbo3_-|JYRJF>9}??j(34G!=iGb++zA>WlR@e`kYGJS;_Ck{^%*mqI|r(Zil9VPo(NxGNksh(=b1rsb*}%8xAw<&`*F z7#UJ-*BknL*P<(=Berpay>S8P`Z@=n?9JEv9D~u`w)Je;l!Q9E_a|OV&hK6$hFqZYh5erx1a##B5U5^ZaLVzx@sD z-PV!s`n=HMXRN5W^5snZZ!Xf`!|#7-(o)&JU^lm>dHfkUPG?4Abi;346mbqtHe)eWDQlyl_!Y#2i3Ok6F zguV-2?-R+3hRe3F#bZ(faMnx^;ANZm6Lt;jTpmS7ytC+T@v!K9dN9z6)C7MK*-)$i z{VTBCN5gHP@b(g_Qga$5PFp93-O) zbcUq@V2JTH6D*rkweyO(^YjK>^^;@uy=vciT~J`rO?vS}mO&@6SpCL_!wwgO(0UKa zlor)dqmB2qjo>L^crt-KWfrY4_`O+wo4w}gY21CYwF#9;at~_@EADR!d!8|+A9Li# zzbB1N(c3{wJ)(=#-f7l%|{+#P8d>sdokq1D2%lsKHwxkLG%bGl9K;a2t`| zA0A0fTx{0{)Ma?JtbwSkrfB@zVE+s_Q@yyuGWK2f)~fyX9wPfL{Yan}V2IDzY|U7w zjc2I6^2F#bUp>-Tvi~b8gY!j;@;#f$z?lgJ|JLFa4KB&ez@*JKc6y2UeO?yK3kO77 zF_jQVGJL~*cF<PNa748g8-qU>O5s92(G6 zRb*cw+Qx+fpVJ?Qdfy-2agO+n!}?W{B-JB7vUUg=!)M~IvQX(%+G0=>d6~f|k3Ch= zNRwTK1o>v344wN^pc+8*=&N*%1_ed_!2@yX#8v2$UAj8Wu!!iT($r5fU zby6x?^>*z}LIu94pqT5U6ds>V<1d8O+430Rl6NF$=`!GWCE>WcbVt>hvLC1jrFwTz z78l9`u&k!STqig|hm&brpA?AZwCH#;g;OT-hohk;@vATn%QreocSddx8ipIyq_91r z+x~Jc#xdZ)jPbDD`emOxaGQP&Ju#7z0hbUHd-Ya^r5y}g0EU^_f+Jh*%O3Dk@)orj zE2okJhR=i#Ct1-$6diS70K@Oh9*`=GGZZ&N)<-6HWMIp^#Fu}d#>u0_?Feu4nArdQft>FiR<9^VZib5ktc zFYd`_Pq+j6>vM;#sI{m9t!fV5r>b17IoQaY~gS-c^qFuod27u>j8J;d) z;ak|*tbm232@jQy;xV&rdSudNZ0Bpnf7;(?bF*2S zW!WQBJx~a*g8O%D_NCK|E5`gZ!uVR3E_8Qy4_^T$t&*itLnECV?o!x9zmp!Yspnf; zOg5HIWS6_HWixBgK`x>>UvE+tS>g0sdXmG@X#2ie*&?Oc)Y~@+6D_Ozsipp&x3_bp zoh3T>OeJzt*NThaMFkIcO6QH31=q7bex$)bU=$C7Wp4h51rV#PFjsS%9Y7&I=v~`# z6Dv?M?^A`25eydU5+Pd~fW~QAJ&L${OB9}#Npv5amA>&5NWj;XS2#Psa+SV-OV_H% zwffCRp&K-+*1onQ4_XoV7pg}_VGfr=zU3K|1X^wQ#1_5h1&pW{aq%i<;&LlAZU8}mz9DtZF|vhRtttyvx5EYKggvBwN$r+pZR_QSv{oB}N7e?F`{|cZmvT`xia$OL zak6d-13E<62!+n{h)wpJ;i>P`NB}rwI=3=v!go?2qeI6+FM|MIAxGq-o9U=Lta^|Y zV%sc)Q0D2P8P7@MFN}RSL30A`$)hUp9Nuqn(0~J4+sr6n{lu5=LLpBxe>NjP&xa}h zd}9wb*`MYss+t5UJ}~FpG>d$ux*T)4^a3BSK->Wo7Nzn8>ZAPCwx+N zRAZU}TY-qw-8{i+XDHBp;)qFvDXkB=YhEu;xZBz@Yj)}t(wez=?RDnfjGfZK!qb9z z@q+of5+OwRJlW2bZ*&cGTK#@;S3hW4IMqTLvebfqtHj@<{3f%?4{=q>It|m$KKyi% zxTI_sBDOfu1@M?PgUgg&(=6abnyz*J%plz2)rESdjmXVxULU3HGaaf^v1fde11fH* zXk9!%+HGy)>ey|MnLFkgxG?A_`TzUzwj;=TD$~gSEM2`PmioLisiW-pKhXIS)jzr9 z|F|9g6;KYD|3`w{i{jCT*a4RmvUy5ZxH;2q3=2x^UBmHBXGyIw z?X>h~zgj2b#Uv@l$##ZE2I2#qWsy6L@phu150)S+Ri%SD37W(#R-tIsVXy#!c8-5{ z`|P&~#sLyq{4&z6_ze?CPfyetKmA}@GeCsh$MMvUh|LqCV>stMz?I;|`_ADt&iosZnp1B=hG3neVoX8#I65wDt z{RI3nG6SQztk(n+O6HNPNY|J0vS$;Axl6g4+ILw4ExT_X-h}e(cue1>Or$lIWF7hD zqPQgGbEEK2%=HRCV-lDk9Y)pdEfOirB>$PI$DnBFSB898xrg#( zmnAXquk!+yvk>ef(XAn(yXfycgY;-_Lt6#5pu!4Pf#3Et^I6oNy~t7Zn;B~!T~AzF z@(`x%hu5ol9|8iNYLR|IpneoZsdtyM8ejc1$3sSQ3^QLtNp8AZc6UHwZy%G@-5dN- z3H%A{4kjH1wAW`TgdD-%NzyxAmTz@7b5~v%9LH{j2kl2K^OK_cUdVM+tT=P2Y@M8* z@Th15GiCj@n*L`~tAC-rC(&3JvZDo}-k1|SEy4xWSmZlBIXVobeLy<)3Nj@A;mV08VYyp zJp6oo9*bZJLe2mkIET<9343lc3g-}ka`K_*W!5E5snbx)54N;&BMKhI9tF3ht`>79 za!k0IiMDWoRFlin6x#sKNTq>|Z1ovzqJinCf0)A)tXblFe`$aSK_E@YQh$rRj(z7q zKH(*1RYtd1(QPAB=7*vKPG_EJ+zb8~u5DQy|81cODV*?hj%Z)%QfqBs{p9fpU58$A zMpN1wV>8(@`r2Wm1BzQtq%+MH3cxNC#cQT8mDH~6TT7Xkyrb@e%*T|Q9DgjCr|NjT zqz$GP~H4nwx{gjsAa_Tk(wXnh>&IlIhgtpb5)JC;e>V z_#e}9#2=sBo|wiT1}iJ7>9F1eh49H!^(>Vj&VRBeC2CeyjvqjlI5?=65*9+;>qj(x zDi;RS^re1gK*{n?Q`W7_xtU@Dw2ua2YXTP-WeZ}9XK_lqmJxWePlLq@bd@EIXm^96g}^xe&iyPb2Q)@d-N<5is~FJ<&dKz zu@nkO0%D5Y;Uo{5Up~SLz+5bJ3+`-bclThWnbUUboH1jwgCv`S4L=aP^fzq<1(4IX zFg-4{i}Wp)jiI(wQ<=C9$YdP^C?I*N$(f60rQtcXie~PDdqd}qt(r<_v$n(u1kTzv zZf?L?FNc9l`6~8HHlUNMo?a@|-$~aF%@O21fd;6xOJg*uMO!?(U!0NA;(Z2JC^5G; zUul_E3DcvP)@i0GSSeFjMjzDES{0VpF}^i2(c}~$mn~@lmO1POW8FTjMOGFUx;DUu zO5=76kp_0svpzt#62GE?`@dz88+FdQEnZ~_F{dGI;saU>Rv6MV557o`sYAr8!v)oP zIHBI}nkJSE#Z}s2`29&+KUBwx)}`X{+w;!07y1v;UY72Y-QR#>HU0bA3(h4&1S;ry zrHp3QcbPXyf)a8N)pa%HwaW5gG4io{B?URViS2_&8PWd038s9X)5>TfJ^vnIoX=LZ6g>)@z!* zX7tx+@{i*Lm*XFPs>&FM>Wv|aB6+rVcWtB3Na|2!pF>I*xlkq}Em#291PDWxz|H0L zo=^)=hXelrDh!wPidCvVWTn5_{lwfcc7`v{oiD}Ul}q(8#k}dyV}S=wfA|3NU+m`V zCL7vBy@mEzPlH2Np6ETAZ?0!QMHV@;ew|Gx7zi+TmH>3!=L=sxjy?3NrggMt3Z*~* zh5D-o-Gnp7x{mVMMk~6OV9q;btx=vhKy}j)`1#(pt?C?4$PX1ymGiDkIipfnNxD4; zny%1#6AD3()k7pwBy|F1$cXE6EY|~;LXjiL=+&zfWES!nfa$bvNWZGBl-%8SUX6M4 zA?FJ)z8vMCR_pMMf~b{vN;vhNwg%jSHs*Wv0J^nqZa7n(Mb$@b(*yU**z;*O6LbS6 zWw>0~uA$-X-G)QchB&L+iF#LDtVvG-846o5mg(vP8Ub38ZZZ?{{5+d7EE?@mlVala zc5S*cXWsV6%yvZM`-lt8(@tfM+lJO3cvXAviw}YQkIrT-LV8;kxaG^-&s(KH{^x-% zy$NwoyQ`K>r()>6mq%4f|8lsqDsGo2T8w|YCB{^j<@kO-?R=$egBd@Bb-ve13+A?2 zGP(R4_WZZQ%765#zY}k&zxv_@kQoz`I~Q|$HYC#!r4jY`JSl*sKrF|LYVIpsP_PjD zY1;=!PSy~V{n2e}KuJqt!C$Qab%aMU-ot$k?E3s!m6lno1it*SyKm}!vnRA9p%xj zoTJx;6!-$E&&iRxaWp%4kN*3C+D&g#t4vZe7y@O^Q@QR8%)*kW-+%9m3dDaoU=S7b ziD|a2$f7s;9YGk0C?&}*ULJek%fkoHuG)Zfguz>d;p6FMKsh*#$Ea+{0f2x^xDsH9 zrw$_H)TKdz$%NSwU<{TDTpgze^8xi7;VVKzT=;>(FRz%H2(sTDbxgVjA1$`++0QVxn{MXic|-s zT}@jt{o8Ta6G1WM*Z6&oUYp6;O^!U;gw}5~z;_ityWetVY?EGlnYkFEg#@)+%jA%M zJjT#NHqm(bhMF4+dlRRL$DgfMmmNdQDW~3q_Lx0$V2eMPvX(r~H*!DZ5P0y#?Gqd_ z(K#QkIO{<*7P;~*+%#+$d-oB&r3-Jva&=1!*OnuQ3>ly@KK$nwE9+=VPS~xbmW#ZX z4;iz9;^=-?Pzj>VUgyaBHIrfjE@Bk)N)NyM9p3%FWR(v$<$a)H%8IRv-t7;r>91OI z+U&!2sf^Bl4(FbY6t_M8Up=erT5=SWC-;3^E{$=N3HZ}a|0$&w((fl7KQ1m*PA+Fc z=;a10H-`d@D=nK!{Y2|tg5EPcN@L(XkW1{D=H_@2B=FIPTZQ;828YX0LZ7}H>!MKE zyA~Vw@>x_O=2;{oFU*aR3{+w%UpL-#P+{4$8FpDe+-_U}fC$ZOp|xbQP{*^x?U3Qq z-CfHnw0l5!oBVBsUL4QD2`!ypTV79#P3QElJo}hR>4667KsVQkttJf)=ItzIA$~7m zk#SG8HhDFflzbWkmPxY6A}4l8h+yFsWG0#zVr`9`mtff)`hu~_5EYJ$nyvFauL%=o zRg&GEJx4INK;-N3uBi@=uDUQE4VmFEMBtyq3N&FFEp7=9E!{y?H?+({wmW)dyp$$^ z2aUdf7?Yp=*^_)UZg##!DeO(~*v^?ME{m)iPZ>CYZ{wvM0j`?DvLwPYzkG zt;``HdyI^pD{e!wp%E_LmZDf1T_fd=NCBLr0$JXatwVM@p$eLEiN)o>^o znv;?j+kU>h9S5I7-B^y&GJ*a<81V?X+3?=LVhlc<$&meU^&06CZCtN@P+b?6jK%gFm}=(%|<$_6EpkLa)Uyg6l*hreN3 z{9(GD?oqbdB(8cr_eoekBkf)M=n-&Y{D+@5IM(`!sOU35sj?;gN>O2f2+zV2;M%m- zB|oK4@rxBT37grwM%^B7eZd{T1K^kvy)TQXQ41s3<2&DOwH_5Li)OE&Qb*aYBd>Lm zj4EZ}tbElfd-B%XygbIvQ`cQhZp{P!u?9t_vIXZeVI0JcgT zPt*H^`nd2<*V;e(c6b6RLWUNH0Hc}4YExM%edDMVC%;JXQ%W9<&=_#sU+FusOjcm@ zUZsYqRo;#?9mmjhE_8PXad2`{T`SHQ&ElG$71inmWY&T#-!+ljQUGYb9b}f!)LOVb zp6sd#V9gc5N&tQwZcq>C4wfRGHrs1@E&f7`PU}{ci%pNOHWL1LQE59zd@IXlAJBx` z8Z4%_u4^E+WEZwj*I<-)p~1Z~lhUY8M8vL03vuZ!Z&mKo#n)Ak%x#9}8cI4lPhAo4 zV7EC7(bq&$3g({L@ZrLR4Yqpao7NSv)DrN0puvb&tjJxX;1WFhRn0oghwA!sOLa0U$Tp>q?Gh5in&4gYZYnj>E-o8Dl@*jTO`MDB^ zMX|0UBAKpr-uC8lpR0CL*i9tZIb|FuQe7o1uBhg|$B28ZAIe0)owcb%{ z$E<1pn59RBxeC%r(JD{Z5~Y_A%iCrH#w(3fy?~83-Y&@n;QRcBe3c-tO5{dJHBE(L z8Wr0zb3dMxDYj*CAI|i|dGzD_=RBT!Z!Vdv`QEDj88rn`^Zn)0Qysy`V03 zwN#b{8aiBdD!dT`yY^l<3g@7s&QW}&bg z3G8TJHR7xANKMFYv(4sj^Nj2{uXm~TEi3J=?)Yt$o4ZvpYJ25{q1}cxFIk5P@btsC z#2nkb`G;zghl|IITU$Kkz6(A6kAZpir<|;#04P8ZYtB4Pz67#1=U(4HbiZW+fN2O>G0!yEeUg@ zs;xY@{(kg(BlL(!$m-2Xk2FHIFR)5jnjj?a!u5MI0S`2e1*O43KKcr^id!0SD3zV^ z6buHBLKbGPu8=P^yP0j38lJkRV8+v@_;V!opNF`b^X8lF{0ulW9=18yiEgVKA28lo z1Ni`3IN1~fv#Z3?t0jsc{5UV9=Thh@!QX`@@mQun%z!qT*f@}+(`M$W#7s{>2^a>> z-&Cm)EfHmr_D5hW>wVN!n=#=6!VIyW0SFGnL{fHw@AZ0_+z&^8j>crn1dxq(?Y)x7 z03CK0!;jGIPg$ljPg(+$o?Q-aZMC+?XCwzj+}M>|CB16xNIYgcxQNQh{!KbwrSG@> z^cl(X^Yq6H96*92LdYO{vA5s62iNJ$?0DICk<_ahPcN_h`{cwjsIIHHF@vqXK*Il)d((9Re`l`GxBfcPp6stt<@$p=+)6trhCejw*= z@@3?`Rj`{Y_MtcRa3VF4Wo}MN&LzJ_dD0-eMOIZPmr>}|0pkb$kY(z$YUL#cOZ)B5 zN(sAGU2u<<6g{>xohGDFxAI`8UBOR{lGvvWi)vrcd28&mCRKo)FX-ij*g$%y%P6bNOB*U6}WkrIv6<616hQ>+fa{s zS~JKp>bVR3(H<}eOzOzisut$29niUcQ+Dq?*L!|Kjr#W(Zl0M-w7BJV+wMi8x?CE( z^g(~`Ec>bT8_LA1a+GzH(V!g*BTbC;G(Uau?STQ$Pm-0CZRDSCiFH=4LnKqsj4!rjJ9_i(WF&qB)yw?y8I5*Pqg5}Y$ zZyjBZ&v~uKM-(HLjt0JIdLWU0IRA9;J0dIu;M1Mn9JW?wTL;}~7VTY(=sC%lq7NeN zVGh5wh7W8N{WEADooz%W*ZN+b5;HqS5^#&o4aoSi*PG3gi>t&q&7+t?O*3wKdF9oU zYsX6eY(YQ8p?#^|E>3zL=MKs(7R=Oks|0rU#w@*~Sd)7H{9_wER(0~34_Q^?$)MMu z$89yf*@;nzXSs_I?RzwUY@-Dm=87zX2?TYx_!R?tf7<6+nV&!%^4s|LM&lE0QBeXK z63DBAmX!VK;3W6zOz&cV5REfgs6IqevV;@l1nj-vX2EFO@a!nF_$)lwX+iCm!ljdG z)lso$l4u(I%B{hlh#=#=#lj8`76=@`v0P5zXt0$2*wh?SU*=vxeJjN+&xB|SJYVvjI2^UO?h629!5vt~nf=1v$1HyyKk$cHGAOSgCb8vrnTN0 z3De5+>G(w%m7;F%t_bB`lJ7DRTeV7z8wrMf+NPi3sZmiJEtE`%Rg^er>|43n8~OLd z58QqS9#K4YJ^Dd!?V@ry@ELHCFt3-9s5MIGxH5`CsxL+}zXALt?;IyL7XV)azVTn{ z$Fr4N{lwijGx&j+O+oI$B66?-UYzXD-5vD{k;(@22<-(+Q;01ys+a-jQ#QRreJ0^% zp38QMsD4Ee|L%z{`{oi%N@Q_;E)M%BU_zljjyXH^Z7mGkkZqG1Y?L?&e{Fmu-zk#D zv0gC~hY|6n-fI={FRu{lEjggh7ocFym&?vbpYYU-<&tYOP5aR%bEmGekUS)YNbW$t zQ;UXlYoIJ$2AzJJru3p0Q@<8x_5af5dPs5RfyESO1#iw6T8yZn-& zZ`yuEoF_@H0+`LpQs3T``^ulYc?ws5#olC-&e@l@N9GNpFpoY0ZdZ%Zo1VX~HQkcu zeVDba-~y-guPk$L1WJqsTu?4ZI^wu4PS+#b(2j>`u<+)qCL~QQcV5XL_o)H4$qCHE zcFG#o0uia?%=Y4TE}M|{8QAcF-B*Bj#sOIAjd8!frKb*1ibzahvtXFUCo1vOpxVzk zHlG`HU|f+hi@*)_AEiS-MA%9{>k#*ThZ^mKFEN3YB*u3S7?#u19~%q&E$%P z4>#}R!wsDduIDcom1~3Qr%Tu}oExZ3m(pNRccoJxd@#Q}8+X9Nb_++u@p`#9`ym%AJHk zPRa{XJlLIj$v^q}f#XA7zC^}8s%K<(K-VMVRR8%5Y}H(vb1q*4wEwmcM)JfYfEF*r zH8gn}T~`D+xH(zJKh?UF%Veq3S9fN0FL07Oa0pD>97)0 zVTxkoH7gI9qT$nFcyeYLldlmerEJ{*#M6JEq{=8BM4ODd`q-RCrdl>=@-_;1liR_E z#7h**Y@Ej52+4Ko3;9GYiVw6XC^U~mYoayh&!G6dycZ_PPuWm&%~lO2K>P9n;Iljf zPexict7Mx%$Do1ifQLC#_BKs%>GhJPA?T^?`VN9}OW0H@qMIeBUeekxz2YhP_cPUn zfp|8etH*0fq6NO46vL;obsU7kPqiQ1I~wdbgF@WY;i5~wOIJ{S6pbKizNtG5a^(rY zPsLuq$jXQRhmE&>Yr_5C{uc}s1XN0C<%QBA(k&tiBF#V=1f)9#3^o-}8YQJcq`Pa3 z7t*QJ#^`ozG$TfQ58t0S?(covzdZkf>$=YCIM2uVr2JUYrlNu7926JN0j%^5M#Ti6 zO;oJ)7V|f9$EHn7ZK=%lk zadcL9j127z0zBA#G|>fs4?N&4xxZTz57bGM(_6EkBqX1AsRSg}Czcw6heppr0X2tuC=LFXclon%8ZJ-N^YxA! zSnu2^6DsXjWKSNcGr(An%BoNr=AZZn`%$fn>v7}9?ly;{JuNa&`Y~@}z`!%m zUA;B1>-+_95z%n(XYnA{l7lK;%F&5ZK` zm|p!J>{RmJ)VzKj^J~M-j>^6l_eZm{s;c|8toI3J4pR<8wClAj+heUz%qzo=nV!SL zCP9z>UYfS|X5rN06B%V9zIeI;KJ6`9{+qy_)r#_gpPT@bl>tTE)H`hvYcWzs+x^{t z8lGm&H^Yh_K%9W)iG_$kN)>H;OTbv}OQW{FPI(E`=tn7bUT&07=@v6~a=US4rmC_- zOx|6X18(F#V{0V5R%rNdso()9<*Ps5OEUPZSYHdA1~D29SuZ6X)>_$GonX=lyGTXS z+RhLT*~L(CGlox{t#?OAV8EC-?YfX#{b}vES*h@4#}QkHn<)7d+WK0`d+yl=zYtfr zYqgEP{SVyDN}0z`?b(`<`Ttaqy4Ov|s#jt5>A5%QOjxNcy=R_bPclONHg{EndxJ-O zboX^xwx*n6ruPMV=qx5jY&6)pfAumE-=hE&kP^^4$2V3(kJ@Vz*VFv+JT}Ad zO?dCxPo8mKNtzQ**Jw1ja6AFvRY zwM0q%G;wQtCuEK=7(8)W1FO7$#@AcfrWB-L#btjre3^c6tUPsbsR?W|{?kO!e#O(F zyd106vk`i$?=s=SZjPf_L23U)=051}7dd{V>wUJ_o)ae*EM#?W&y$Obz8nzh8>dW2 z1OqEn(EwEVHIUboAsqQTrTKEd7Tmx%vH}fO0G{8Ny->3@Wdg?v$ z$)u7X-vE3|!&~J2PKxc>fGJR{EDqVk;RcMCpP}%nyO-FMAl)>65ONkYd8PY2@6z?5 zRmBD@X12Tn_5Fqb3*OHAgal}$2-TaljhTI@{tq|xTE+Vp$m%JhN%h@pE>0270;7?5 zMC5G~Bk0|fD*WVziXGrl>)jN5(<)?}>EwGE#$=kJd;QG|+J7t$6-peAKC4a1SBaM) zji$*YVk76;v0uC~SA7;LrlROgyFJow@viKL6y^*d zfA8=@ReHyfm;86bzLc;F1W{RLeQfyN9P5P}Xm_7qA2uL9EQzhKtz=<3h&+>3!`)NQX`y#K*`A4P*4N&A4+9*q z>D!K93Nb{^A`&6dzt;gz2?<);Ru9+!?rPYQ2B-~kE>{VnU~4s3q9nVeE6thv!17+U z*i93LheeL73rR6G15Yz$D=^IBUPk4;4{R}LeYWn(hOP}>V?JkKU0LrXu(jKHW~sE- z3p+@~x84NKso^~G2hgkdqgm}#KO;AMrb6{hz&Toq)BC{Qm|@#ijs>5Wz(}=jqPSkL zUt-I1+L7u(FSdr^#Jgmd8RdNea3`=|;gdX`T%XY^uB69_f07PrzbmR>JSl}euvwdV z@K9_GzT2BGue5P$+M_(Gb8vomkMbcGTW#2ztG>%U-CKPtJiQU@T%1uWY6ife7qB$( z*ADcRVIw;dN?2vvXMUVq^wDa6{fEB?TP-&3lpNm?cS;Vt@>;C+4BZ{_$#zc(Ie9_@ z*&X2-S>a6Dm*hnyy`!$r6hcHrj>Pex1R|}VD~f$5_jj+)c0R)MHgrNR!o6Z_1eh$4Q|2k3Z>R}r# zJ#BDx4c3}fHA_M6T^ zb!B6aCSTu8Bi27I-m%8qOTvpuDmoD};h=eyUUgi6=aW-ws`4K)lHU(GSh4s)Py*6g z5?SxQ-}GfVz~SFmT*DjDtJ7)Ri-*cs)MY)rpue#H+%`Y1@z}B)JXQ(_4999&w1v>! zvlmqmMJV%Z5~on~7v$fSn2xPBdQ1aRLwd=!NC+5hgC*?Jz3_tw&GiIjLPQ6X&KtYe zWnE+XskG*CZw+i|5^3Ll=G_ljy+fJjOkQYS3L;~aLx-4(YxVakG>@9?4~!!|)Ja$8 zWy_0w=ekyve6cUL)Sb_jBlkt(g1oz((J2v=*TXU z+H8ksZ?#nf?Q;oWXM;vZN>Y&J=BI#av!}9Mxuu{L-5_-=vn^EnIR*OmY61#m%d0*bj23z2rR#+aLx-fhrvk?oeXuDrod2sn;-l{mX zasP5_=5!?AJG7yK!}|&rCb;9Vc2VBek#yX6sW`XLk_|fPWIN84gNJ7A1y#MjM^-0A z5m@NqHHp0%|Mj9L{8vt);Jt!w9+lAmoZJU4LazhDF7DZMb@`ji<(6|-qV3U^Szu7P z@y-Pg!OxWS&Y-~M$E&G1M&U@SJ((ORf(yt}9=6>qTE$k;VSMUeZAo{+=4`Xz#;^?G ziy1|>V4ms>Iye6W>|QTQOPh3@>FHa{+1TygZYsC$1n&0jehQOTRJ@1gAzQeC&6Yqv zZMl%<)tOlaC>s{C5w}+ns6oYWQ6vnpSx^8$F2MNTxlCb=e2(_Z42RH5wmw^CQ$Gfu zgQC+PTDbr{-Wf^M9vIPTFB-2UJ7cz1wi*Jrmy7RWaV_8UWbFzJIpQb%EXGERKW7^j z66fBvV%A5f?+;Qpc|7;aY;@v>M|^BJAwAskgNjcvvRTXFvh>U3W(s1B#`G3JEF6ZT zUkv;#(kb_1_>y`m2BgPuYmv*QRCx>ZAi?7@yyqoZ)c+1uj?k%P)R*a`v6=o171^9> z6I64I*Z7ya-AGFe^JSX?Fzay%K~ z8?C!p=QjTjZ`Fo?2)erF-P9xCBjivNicYFe-QuMcwYAnMgbdGChebV-^j^*T4YB?0 z2+R}e-OBS^zdPv;?6z^?XwD}mK1{8Nz)Rx01G1u^d#NeETUURtrCrp9BEc%Z`f}L@ zOsDeAbMIs^^rghq*-ky=t=cH+@t-|lq_TeKKwv4-n(N{;YZwyf%4>k$0P0TUMUyV| zi|gAn6-D%(q15i_WZB|B-j+j13J||=$@S29xNw*qj_UG8oGCw`s}g2J{jyRNZKV7z z%K>GRcCBk{TMNUkei!;xp8#BAT<|*Y_don4Pe}Z#vj&>Pb90Bn&foz`0p-Kq=f(YB?ns~4;xAUJ*9{!OUuI*^ zokuGvzDZ>6!+UthYMk`lce#7tv(tMk{QbAT_tfnFZ?g}&vef+7?RyS9_iW&jzA7b3 zC#5rWIz=j#nx_kczF6lQul4%&MGYi5j#g9q{R-}x8!*Q9W@~mo=hX3EJGDp{q9$D) z`oz|f9vCOLm4Oj+z#=Q`F@O%88z~+LybEts9jJKIzyY$1@6dEPNYD? z!jGC5?N?@2aohxaTd9f0$7k&Lva+FWjEUmnM;{QXUEi@r)LLJI%D<)t%8Y=#si%(i z2R$?TD9dl5m-J;P$^73$7vn7k7W9MDz^xhr$CqJm&qHb_C`FSxE|1mZ5rYgN6X?#M zf84^VcXf0;#qJ9h2buy0jq8V^mEzzaMDao@AurgFloam7+L`>OR&m0L;gF-gA=dKB z-OFoAIFgF;nITF&Jy}0RzrHv@Z}m0{T51h4N8(3~>(@%zcr3Luaf>F3642AO&Gu^9 z8}}@AgRgQHvhy317{AD{0g#*U|*C?ojWA%%1 z_F{c$tYVm_%0LyIPK*FBxta}~O&ToA58Cqawi$0+f8!HFoklf)RoAxMeZg@Sd*?{Y z=H=-fnpq`NvMpE0bok7iTklHiZAWYQ#XCtN5Wl1j|5tYrt%SJHm&$K&bg&~%lQsu& z+8faGy0)-q6{{uDMP9)6L~#VH=tDb~n4Wd!WI&zvD$akmqA?m0MsDcXRTxgVlD59A zLhteyX4vS!_V3cw$WqSkH?z|J;i_}&zak7cdK??$U~`kCb_?nCQ==>^rM8aIy9?1f zU9iiP3qdlJRM|UuwA2-(n7X1GOBL6-$1Rk@flf)gvo;${gokGD_5V#=^df(Hn8woc za{dioQdjI^<7AaSei8edz3f#7hUzk+m5(E#*n0UW5C%KY@#n19C{d29)rq`!3B;GpT`w%xmPOwO(i&pauT|=5y+*J}@)xe~2x$ z-2EqbJiOJ_2}!)xbDi2wLte0IBiPb`m$5ZOGr+<%J4Z2g-x zUGfkjixc=Ht&_S>1Xm?w1s3_J=@nW%c~7u3PDdNpldGz#W0j44wL%k{_hOI zaCwX2PedVVO;?*PTTFAEz^ApxB~~PHo;AE~2f)*)!n)(KqvRgUU9Xvy?nXb6hQOX) z65MAJs&d2=u+!2xa8Gf%p;|>Ga*iIp`kvIz*0Gi2dpH(~lXnY_ zM{y0b4g64)_(wuz-S#vZ;+2wE-r2`GQTFcNMpc&w3YzW=cCx^do+u<@As3#|Y%Mv5O-Qo;que=!;39I``sfD zDH*YU!oBB~#BU~^)wr%o#?GP=N~IGU?Lp6~t0@V;l`VM7Fb0&%pKN7v#P{%f{`~eT z>N>HjeeEyxn zF)rWpo5wy`m*x>@UjGChIYJ+7?147gGAUop>y%)hUENMa`kO=^L@9Ix3T0WXo`z*z zkxie^a}AQ;!@?eibwurqb?lw(F9gBAZ9!Q=je=KC+Wapuh5(i|4<(I?_t9!S_sFW8 zRR2FzBYp+F63lLr4L)(^M_kntP5bHW;Jf(-Gx$7eHph7%hN^*jtU$aOV$s=!j~$7k z`+Q0tE;8KTo!o`4g3mbPL6^xrnXr!pQ|6W{&QkB?j5%OZQRZF$M8I9 z$pR$qRwJIp^yb#5+tJ>FR#d9FA9**3ZQM7;DrL!v0?YA?&#@nd&zf{}eUTRc$@(l| zZLOtJg?fE%e@$!@=*}iIrFFl`HA(LY2>h_{N1Za^EsmpYAI3J-P_Z8#3f*l3{Zis- zR&l>y_5|>j{Cz$%K~Yk`vN6Sy3a+NcA=vy{ulluqrXILf$F;b+Vw*vCwS7Z&s)pvB zkvp3(-?ZqY=op(dP7vMgsE80rqCYXumJ`}+)q{Oxd2?&d#?CGxamP2RQOC}~oCq1( z{(Y68^9hE_LDWRAIG%Gdea2`3a_`wp53ZmgYT>X%v9khSsRoAR$jO+LQKT2+}`T2>Y%{5aRz z0#TWGgs128nKo0a6%iLoUaC_Rn<+0qUK&+6&NONbN;z!#FNN>uUuAzb@5<7VA=FaY zU%$xMXh&xSF7t!BWKtN;v zIU9I;L= z)nTtf<_=q4Wo=8TE_O*hsu|9gl7#iOxPS)=O5oHKzdZ?!;J)WvMJ=y?rpf@ajNGkJ z5$*awsGEwJuvRCwLJ1J!cr`(v({eTT7J}^1xiV_DB1cu$TLoQsw9Gs@b43y(!@gUb{a6lqos@WY3(E1KX&%Hwi_V{}@&fx=OHdxro zueOf8N_-eDR`Hh)KzU-oMS`BQ&Fg^tNaEhgfpw-bS%VbEZsi>^ypVDZ?^}qVYJEQN zm&WQ_h|pL*UP{|g8WuU-RVUS01twX*hy5ns6hz2e3UERJFOcmCrH{m*dY5tp^>!0N z<^>#WnZ>bB?fYR)0zd5x6Mq%)h9h@kCCx1l@Jx|Vb>}TX>@Fzkiv*&sYqmi5vO=f= z6PxQ!9%jkfTv!M^erK^;Yyo=oF1^Mui#Y_`1eiCbFgCx{?~g#vTyi@v1gXVK?O#u! zitNZ@70~hqi3VDlyM7t8b9dLD-11(0k%hZtovH(&qcFHUUnahR*+t&I~3r{iNUG)&iv-~am$?1aA(H|ZaDJm^9!pK6a%T#27K-uIY_V~8bf-fl4I4Kg#r4lH3kabxBPFnjembL&+)FdLFZQP95d#* z@>UX-x*`Z1JF=q(s-oAJr6@!jU1tbl32-67dAec2)GfrV9K4u}VIQGUqhU6Y>LzyR z#UM(sTk+SAj{KXHAM+j&Z~5AHAath+ukyDu)AX#qXVX-*Fg?SEYczoO`|Oq=GC{R|L^gF_9STtw}DlWEnJhT2a&>n>_cx(vLoB zy-$m96LatMNdbn6Q{!qGIP@Sue2rTwf}X2RG;~j*!AdMu>EEEkN`q|QWW|*~qf>j; z{bY9Bq4{#s{x_4`8jbOl=%8jtz%1&JA?2~%*Nr&XF3QDAsccB`@$jvc`d}Ok6g*vUkYP z-Y=cl|7OO-N9p&^H^l=&53Q*e*N-j?2qt8q;FQaJA5$%&3-6*Vb#6@1b?`KyC z42g0fjR4FI+baP6Rc4(QLMD1=)Q1iIPp}&l8p{qWf4*Zgcd(%ud1ukNlO0Pf89dq*_R^0`TLXZYj;Ypiy8Lf2Bu~FVr z{FV?H<@euy>Bg$1cU5)g!B$ao`}lz`MCGRGAPN`L;>IY2TpxEJ?T0*fi*o(*$&cp& zw;($qc0y=wzt^IHw9Wa_R96uYIyVK)_&cp@ReOHB-)jJ2z&ebO9d1Y(&~A#9$st;Y zd2E`?QXau9s_Gt`XmKEV4E!bwDjmjET*~RAK_b0sH%)GOsKno#6df>|uT?C|K&D&n zfXQxwZ)!{5;Bd)hN^|jwhgCDqMkR~jnvS{Iy30(Kf4~a)A!Wt0Xm8R+!%z){hRs}o z{|*7a%U&U~q#u^pOxt<z{1x3LF^1*@}l ztE)9LVzk7lm)NykA^h+Am2ZLpCQz$0cHkKtVR%L(Rt>P*iHp>56-*p2avIF%dj)(i z#DF&Z3Z`H_CeFFAm>-5hpO0RDH9}+Qj%z3f4eP(pbLTCre80-4p*IbBz|-qa;Hqlo z{Nm4_;#(aX`$&jinK;Q9arc}21B2jW1YE@>f)4J15y6?}Q-2OUJgCK|)GC9b}@LCK&xEunvJ%X1&R zZq~KV|7c|t4Hz86Z*cgpO+qo+(mMlWgUQpUmR5#5##vU1>m!x>XVR5dK7TdoRAoP5 zRc%;n3V%kdhJ~2}n)ndocI2g9%&Q#|0gA1B6ruKi6X~1L-~_M<^&&J65X+9Hn`Ymp zd?QG06-NIvd@FfpFgQmzTYiF;$%D^NZHk+p!@doIA4LzaoD8C7 zj)bi26>0D})X%P)uU!+-ohtW+P*sOm-a5CqeQuFu*02z?&EWdo457K}ys-@dl%-=YeLL?|v?(uC72cCSBeNl@}9j;{wuS@ognB)Q2Eb;J=Bm zCjy%`SpC+RI%_jMiu`R3{EiO>_kcT`)~_+kkpg>W80Pv-e&UshBsi|0#vICNOUTx% zA{}~+Jvxy3o`F6(Ydbokl?!B3^sNkw@Y|aha%Fmy*bR!+SFEhy)4-4E+WQD`i~MVq z(vr6S%<;Q+pT+Eh_^Cf`38?m9!r129 zq7aV73JyoaAf;~F+n-Nz{1Hhsv< zu(C~*c_on^{kl{r3JFIW0Cpe*B| zzen#wg$E`Pg;^4&JH=dsH6GsN-<8NVpKrdmy0lEGOrpLic^@UWjP)3df3>X8UHd5M zU7hS-Ur*`{#VAwTB^TVFD`Wy^t(X+;2fJL51g51Tm$uz=YWKAzKBE=?U^P}3AOz5N znl}&EQS6#?&UuvZ57qDOIb!YHv^n2)r`biLRyEyrG>Se}wW^vHReiu!+Wl#55ojER%AhBAtp3S_r{;Z- zbE6=qOVyO2H2UD3W;>`2LRVoeF1R>hrfThdr!}T->Rzu$iVAbdvgMlCx(`BhFej11 z9cZ0ytu@$uQJ2Fu277fHQ&{kA+wfHC#x=Up$$Gj0bF5T8g86NFGOw?io9-4{LjrQU zsfGDNdWxI0rh{uShc6}Ek6Wv(y1b|4j+u>NSrIgBmEUp3t5;dos|{DtwCvqVY?zbc zsiJ-B<5{E~@6uQ<=o-0m#a(zHKhioTuLr`Kz_WM z#S{M7KLa+_Ue&fgE-;+eFZ?&3XILg;KkimC>ZGB)7)6;F&b= zQVH$JkZ@P2UD2urU8$4X``M0{i-7rYF2PBE6C=TZ29@2D6C3houL$Wg6)a3(l$yK_H1JKBNxEuwuNo&k zOks6Tmr+udb2Tvjucs}``Qg!)_+w5G5&Qt3{?W%MW# zH5n|tf`*O~S6h!Z0(TZu9zD0lNX~g=GJs0_iVX|(qWx)Ro=+A+`CeHaJi-oWzG%K* zb)+*rP4s~-IMCGAa8_LQF_^pT)Vxq#+hq$LKRu6a#th6C6!&@sEBPb@Doj=)NL51QTD!IqtJIR^-h{;_7U^ zPBAGMu>XK`xU{Q1i7KTuqVi;)g7<7SbxKg6Z>abFXP`eTgj z{&BlWPU&;+XHZ|*L2|&;5wrN$5L}2Yas$jf0e;;QQjeafI&*sh6B?a1eF%o@)q?jF z7Rt|_BauHdc91gwKHb4#f)ePv>QB!LBn1qxeCbPD1FvNT%WP3f)nv1ngW;cG&QGOB~7zTc>7YH~FWOFQ6R})b!iTQ~HcL`=|KuMl`?BGZ+$g2p0PDhv$&qL$Go7 z$6QjY*~;M2^iExAfaOZ^w08F|yUpYEY7#kR4d$8|_a^vFutM@kT&=Q0*wAHan;^_; z|5f%Xrz~Qwz8zL$X@ND|Nw2s(y|^{AN$%xcfr^l7u1@UzIh8e{1^-fA)uG$goLm~0 z+v|G?f4Km!?f8yt*yXM$8O{e43!PcB9jK~VYlb9MX7vL@_QF{(f|kdxTesO3ZfrRU zrQf=Gg8%6ondw7A8Va#=O;y|}X)r=!rv^}W>pj@wnLW2)!Fqcj1Oz6SRB5Jo&?4cQ z1>?}PBASggYG<>^zl~6f0^RpB9i=8U=meN*sGX`poNmEJY`)^1pZM^}@!X+oI<2hy z?MPGGke5-NVxeqj)kZQldnq5`&wo1IBTfo3z42H;yr1SVgc!yCdUP957EG3IKD+JtSa6q?&l#GoU2+MS zivgGVlbpc*!~iyb&zAz$olkAUC4~pSaLEjaa{q9|8<)Lvl14BOjL}Vgo<%2Km;Y1U z-;eNCQN94i+bsZ*a{__YB1{E|7|bHIgFp55=m2Z5D)XG1zW!9u8OIC|_qu?ZGduM* zH)jmTn;MiENh7b}d2Ya#j26+L{;N_oy{d<|Uha zc3A}Y97LozE&b?o@@L@}J@B)z(p{j~9p+(u3MfJ`wo|v5k|HUl4)xF-(5WSI@rj69 zbD)YcsHx#(W!Jr2RgL&Sw+Ufrzrj9*HcpDN3qMMG3OE-fbtg*fPf=F=2mwG*g`ogr zp=MbJg@B5bBq_$g39sjen-X=EIM&u~Z@v3eOTJaKyA=RY`x{9vtIKPY!D*Z5;L%2N z{$l<{L5KE7;^L6q7ckvGANHDx4cT?Bh@1Yz*9wH({;zD!UdTcb){SeEB;H9NK?>Cw38vY(#m_`J!dfK8JnRrf91t9Hs@BjZsH z;jOnxrK^_^G{fkZt(280>fO78ff;ody8fb=zP?Wuo}Kc9-KJPo;HrZ1&_UPVvC^j0 zx0T!X_uzUm9&w zy7b=`@!sC`9s5hA)g86}9t!6j^oV<*VX42UQ%e{-Y$n;`sY*9|vM+Ct$H?=J9Vdd7 zja#TAVd!~_cSVh>|J#2ZRqU**Ht@8qMpg|qzLZngGjr4`Ve%NVoqXQT7o6@q4}#kh z39_NUL4ftCXuaqFWuWn{Lrt$-kIR(Y!nQT-*fL&;$nreA#PdaSSPI98O}{`vW|1Ud zyS{_(`9n;-kouhcv@}6W-lO_74S+t7&_B?O(c;wc1}X1gm7OEp+c7f<%-{@&tDd}O ziX*w_HE|wXgLN~?!jdGT9IUYjZYG3x%P-G0QTqKA5Q4SFkaq>oM z3I|U056BDtT1Wk2l9v$~i*oa`KYq!k@1E>(E!H-Gmf)>kJbxf-Jf>207if~q^@Td{ zm1m|~&U}GzmFxN~vRe~%OU0VwR{nsa-1nA4a$5YxOZWE~0$jUI`=bI4l9RPjZKz0E zd-;{2+C0&s+Tn?Z-w!WhwO_@;+>N{yqf@wKNRUR$;*W1kC5>COj#^xg4l>51l_-S@irNBpw1J|N!{Sm%=@A$bGgsD%co<}74y=2~1 zLQAz-0*_5U?w^n#@UBp~iSfkuO*M);&`Bi)7O}`JfnymriZ;ixe8u3$pI1EQ&se+x z+#Lt3hkaxNSeVF;&iVzmO*!*;U;=!0d3Qk2WB0%3r$OB0%0B)Svwp77OYt4 zkyM#-q)VvDwEaVfw3=wc$mWyOe+iBaO2h|p96~OiDJ@ie@RxtfZ;MMll%90Tv}>QT z-~udZip#BtQKG?O_ZLK{N7gh|sT4rpfnl)tl?H9}HO_zb^4dv$?<_zGgYS}{vzRI! z%X@=svix@(6Q_;2F-B<6yTO`wN=KM`Tb3w|#fqh7m^wcP{)UGf)+oWwF4%4KZQ~q# zM|CT)rrsLou9|BJeBdtqa(JZ4@3HtpsFL!iv<$t0C^kSH!AR{6>d<;(ORHQjr-_4 z;T%jy{pR|jo`@|@u-@CkdCgK)+;9**YucFOHu(qyQ+dSrqsS8ir1~C|m0a*xYP={K z7OnjX`!QEl!y$y~4kbFSpVVB~I?OuY*g7My)*w_L+-DH=+l<@9MAu8vHEK}bT(kJP zXXuDew&);{lZ{RBE!XK-aAKjqZUg51ud6AYf7dNLNPA~immdDVAUh=X;f`afFo&?K z25Bsf<+*|Xps;i^hwtvNWPw0Vd2Ud6(0(6P4$-gjtdfMEKKC|oqd7kaX$6I6)lMID zQwHV>(@+R4vdiEXtMs1)cQCm^+!x9@IvwDwfV?ZVSEZR8zmknKVJMveV`h&;HIaljc|J&~RpGy>t?oa>;o5ktT zE&fPXk<|8?3m&~2zW{B}zRT4y{`Dds%e8;<*EG@SU}2`t{@;BCMLqA&;X@0(5yazL zaSo{;0p&CZ7$q~%OK^%#ctzH)pW;_G{H>YY+rUvdeKegbwo?W zx$tPh;B=>FQY*`e*5v~8`~lQdrqRzxHk9MsnA>#C)Y7EB^E0inyv!T7gG_y{5xIEP zJt*H5)`v{I1fl>Eb91XdGH<=v@_G)U-zHjAL)%*xk|D*(6i))? zBwScRNa^pK=A^8$8;!-2C&QVFUpijwT*pPYqPH30p#5CeBgvjoyCp63bhKLS7&hmZR~JQxm6z-{Q{z%7zJfscn>QAxRECRda#!I~U+uy0 z@n|=8*G7ie?W)X$bgxv%Y_~`YJ=<%j=+{w`WHcx&5x10s@Afam)2`jxJ{V7PO6+-O z8>Mdp$^xQ!YWOK-q$uKCEI8Y?6bUy*XI+*<{v)&R`BJW!rD)Cnj{NO!HYwq?ukL zNESJZf+rQ;tK!I354HK0R~|DB4D1qlE$$l?fR++#nMCs0AK$c=B%VguACy(2S2mny z?X`0@^-drE0v5f-1|AErkY2WP3Ye9zeAO&UnF9W1S-a7ztB29&+*cbNnox`t(ilRb z6FHvW*j$sJNxv6p+WQ7mBxoEJX64#*ij z30i1B#`G$AefD#@uVQI+v!M+&ur=6rm3+)q>hmy$3IHxW^l6V z8EvV_TYBSGm1cl9AK(<@W_@(yr&Gcg#%r~1W+@l5f@f}eH@(&CJYLJbUpP%;BcK!` zT&r{0GX*)MDipqHomE&+uV!t(VspasrdybnR^;6zRxQOmq-l%6{W}|I#3@|6_ZC;* zIP5+TPscB8!7O+J-uebu=dv+X8vIF4*Q<@;ZEWAL9c$hLu6dNo^|P7Yeszck~MGYV0wHnXK&G(L0Okv~>el8wIH zA6>B3f#aL$R0kjNW{V+4gfj(G2cJ?KHW%3y3!=w-&|gX$LA}2oR0|ul(i-W zZd$PAGt&N8e}57-aqJMazRgpsBoNWh z9WW1zf?q~uPopB4;Ps^n3w;MM8fPIq$J6IA16yHS+mASTL9(2VVSOw2{(|Y8o^Zdb zt@7R(@()nckfyNm_S(fo_5t~1Z}g-rJ-$VR6RZ3;Z%FuCS&~(fg3z3j#}usk7JC09 zm0bVsC- z;aOw;0K1E-01=$PX^3f$&p9X=30>xzi?Q7LW<2s+9GU&m`?P^tOf#1%(96tujvJhj zb2H}r8+u;S{tZIO+Qvk{?k)|&jO{VVo0irszJ0H$)Kc+<_@Hw;M{fXD%W_7L=It+s zH3oMN>|2)5Kl1)ZehXucB@6nc+S)^W3sntYhUCK*WmXJm9s=$?*$NhTWwe_CAWbUo~HZTb}hr{Mfck zPrrM_Ua9V6BJu(GijS!{K+V%xW!FcM!V>4aO7)|yg5BJ$ekq~6rXx1v2SCgg$+T^% zL#S3`$duBvnjo9X`)L%$Oyh{?RK}8bjy8>Kq*_T;3Gdty8nia`K+91%V+oI1`|AKB zZkJd7=z;Q*S=8J+eOhF>R8qZ$rVW5ymmNa5Evs)NW1Us{R8ZdBo9U~x>9fgc+4!H$IJG?#yj(>5{_iM0L@FXoKcZdB86u+i>S|WsJ0EX9dFxDI@Bb}@t z??K`jlsU6D?i5tw48bpXu0-gksOEdTe_c+btZBY_(_l(s@sxD!E*9!FP1(RfHa`wG z3VyE6e|Eit?hG7Qo%N&b*Lnh5+6CxK{n`)S`ssz@MGbxeF#ku&8&G0Qb*b8xwv$rAG~!`1+fDFBB5Dsu zH$p}EkzJQ5&=lZPWNqgMecj+c$P9Z=@N za(hKmrK9DTEO1HddwC&eV9zR5a*+O4fG$N>5yGkdbzw~GBqaO0KtcI>p?!hSuAryU zK^qFRu5WG-CsOv=sH$pGGCkG!!ihU&2Q)V%T++%kDEt4h@z!rqu;2FZ1SPGc(kdYx zQqrQJba!_RDP2P&E!{&%4c!d`h;%5;00WW&LwCN{^PJB)@3*e~%l-$}wbp&FwU;h+ zJdHTZN6x4r&WNFMHPeYPrI9MZeMBc`@T7Dw0x)bAgf`YnG}(8bcz65P+kb_xw|iYtG~jVOK7Lb14ul)pNRY=$c#m52re4lS<%P>6iTDVFo2)f(iuDB?19 z)b>NOb=}SHFzluM@mc?=2-IOKw`EeDRHF736_N=$$CPV#Z%h-5;|W6oZAhlI2ABZd zvUV0wt6Co{XIV}pw2QFc@JWnaN&tyUcCfl&L`e#6dug)j8ZS?tK63#2qiZMZqheen5%oTa$ShtSwevh$yz!F`TX}W+O*3F7K*A$4&j{HY)sC0qMzSI! za+IFh-z2TmoIBeDuPu^1t09ja0-tWU&mQaKadOklk3InQsgXZcDtl_ns$6x{btY65 z9Jh8`zE^%_-ox_aVs(tQj7bV`P^GO`rD0AR2E7ou6Gg!@IS)rR{f9b~v(}~lw`9s4 z)lc9XsIm&-YN9+nY$Qxsd;rtrC&PNeJ$-!0f0^%R%WbTg=B zgU%IiUmOr(H|L1?R8PFK1FU+8+@A5Fs{`-3_K75pWRU)=~85rh5jVBhpjUm>gJY7+nwy*NjrbWjhw%Xqq1BeiF@ z>>!q-k16bnt`G7%IR5jo>jnBjHpdu-OUp@j3&+2m_vQEnu_in~b zvy8w&a$VwhYA5ELhxa0DpC@WW9Pcs>A6h*Z(z=n3w}jLllR75&HKogL{#X?Sob#6; z&GjJol!N1LoR{|=D zBEdIJ<&`(L$$VP7X8Q#}!9`_l81F(8GAZ3UdK*9;pPm9h=g zxiU;pQ)1tj)5U;YVUxNJ~#foo{jJV8BEtE z(42oTScTMn%M3!@ol|P5+8Ms=t@><_@`sG>jN`7V{Ve#wforp$yddLN zht(Rrd?7S_mwymHPdejRnys3~_3^+6opu6JeuJIFKlsJ~;RA%v^AZu1Ip$7LLE%g7 z8^u}`)QRPRfEwV`=F{#zQ)8p#F(aqS`mQ+nAI1YA@mw+Tk`V0Kkt&RXlo_D`h^kWI zXmNn*Va-D^Dxolgy0fA^Qg5+xQMy(Cghud1?BLY?q^LvPS4@|kRI}W!9{XX1<&JnZ zfn+3elZHw9xnFk_x_zbOq4WW^P2;_CT$<~tLGrSW&Prl5Abqaqe=cU?FJ1C1kvz;d z95^tvu3`1ozuju0w63C&NDg7zEwA)-)3}I#mu~F%KZmB=?AVShfnv;DH3jPQb$D0h z*@d7^2!F0fMWO7ZVjvoX5PcjRvYv-^?Z%^(C9cyv_U6%qVIn%ps}wau5=q1L=5<#0 zNv~%41WnY{N}_z;<{wl@;@mo=<#5`G0dSrIYZ`)`(Z51NDe= z+u5&lNF$(hq;&vNK!P-9o@PTKd)7b2c0EQTWt7UPm& zPRzLve${i0k7t(x;=0Z8f$j>(R_Qz{FG{%|-+}@ra`uL8`h&Au$~Et|G~#u8l(c(y zc|_b1Z9alJvU~9TQlb{PQ(rL}7(X57xzshXr)R?mXpy~kq~WY;=Zu|;3tHZtuk>wP z4(bAGtDksFdki!Tv??DoRv%_+`sQVl$B;JcRW}a5^g(p_4iv;H4~6T{H*a~gsi}=C zwsJT>B5DR&I|;lRcXkhAvjlL*hvDA&{o$HUi!OQ|i=}bcw?pwAuTA2E7t6i_{IZ-p z)mTmG8Fo!H5I@RgVW%AhCkl$na+_@^1|4Hm!pVBvXO}mYF6TRFw5L#{T9d9P`Ulq> zS+yJN-tYGB<4M%cD<6ZSF3+n|tp%pQ>u4C>radNMA4unT?lsioP1fO~ZxcM={JXkx zV{<3ElaTgRvs0;JpW5><#~_5HD`{PDAB)SfU8@}n8s?sg$!Ci_oxc&raT}f84my<7 z;8G{Hiwi0EVA)O)a0F^UJ!t>lmD~KaHl)eLq7Zr&NoUNn20}W;)eoAF9lsBBwTVip z{WBiGLJpx5j(Q`Q@J!!I3gVEY$vk}t3}PeWfm_Ucy>ui%Cy~$266{$o1eNFNFtkS* zoA+k2QiPSC5Z?X>W(*`C?cZ&mVvZnnmq_qi8AzuE+B1P#>U5CULiK^Oc!SjBv(vFR z+-pB({us?s7QS;g09Hk_7fkcFS?UPZKYCTjxf@+(Pvw@+qw9;NDFz9A?WYGb@e9qf zAa#zaXi${ugU{W}cmw7D`>*j~V-yFN?d$N~SE3Q)Mn%&|v%SmyQh}(akF_BXxDTeI-=JwaTUe z?$A7t4GYc^E-_`R%+NjVzTKyO_bE-ju98T$XpcL_tul@cqaL#T%&z``Dk~4KGrn(RAYN>a21> zD!TMs0v1k7v$jdZyDX z^Uf0~N_SBA6D0Wds%hq+#dBP0HQQvdB5zqGFkbBX3EJZlxbS|Wz@UothY|)nk_uNA zv9hy~-3JFQ5Q8B>2$opiBAf3Aj(t!ek-S?Lyi>kim$)bG^2QmFt7< z=6meRk(a(&B-k>LB#rUX0*dde7otlk?zNXN)@BbK-fAI(FDaZ_!(?9HX#*749=Rp? z(%k`M0ABCpJ++_D?6phbRp&PieL4{%nbU}-B|W|S#PysZ{L;dp?|#~(x5>a6hoQq! zfl@(0a&0K~0LiV3h-H5ty3V`0E zFm5FlTB;|I+{EI<50oTARMSZeyL8eM8=er$5}NkM4+%uAEr}-4OdH+Eb}mrBO>W)~ z-OJ~iGiglDT0S2h^C`_95tq+3z44JAQM1;z;rk_Xe9XH?hxR*Wq-zK%jG)Wvmi5j} zKqt=Od3XL#N%+4@e7%c_B5*$~Z*+frJ4X5-lG&dF;fu-P;4=4Jck zg>=(9wlE~`s+DQZi*M8^YTq?Yu+sbOp~TQ(hWO-ws*R8R5q95rr4m_1^qRJ3Yc`&r zqd%<3uQDZsodfMvo?}Pq5$(+?^^oes9^x_PiOYW0)ksxTD$@yNO~~#u<+=X@dpDeW zdj=z(Mwcgt^VRu^+e8p9*`*nJr}!U~3qI-n^ke~Hr-QpbOW3phe2;t@L|@JR)ErXp zJ`}geYsL)oi$Zr^l4oT&kwB@E`dy@t+Ji00)G#95@#@CFd_a@n4;=9A2GSO2`OvX6 z$TNvB445+Ea}bZrX-1iGT@R)GJy)K;MV)H3pRmC^&tI!V-qbkMCNXh>)tC!LF?y?> zD9kzJfkEIO+7Pck51{R)u$BU_HfQ%$3Eo-29{Ii%X17jLT?xciw~3kdRl>|~$R*8p z0?^O=4ag|yxP3{Wt*UJl@8mAd;(rL}|Jy{T<#-$87(a%pTfP0hCCDix0 z!A>Mjq$l?gW@JLq@hEy*_IToo^q!g9pIif{{GKi0xT-6)DzVz0Aqr}hjXNy;ZG0No zF>7?$hQjf6J2_26YTlD;TI+a4oY(a!U}pi=27l@2Spa7-PsVR8fD1SxtMPX=l8XgD zKQat=fnP@ykP%<6oTAJlFoCt~xxYTd6gJUpruKg069TXjp_kDq1L+&i(5!Rf+aG<6$kPkWv&V zGDAn@;v*+yLKn~AV^O(3crmCbxthiBdLW1=&|&5SCj{ z_v{9iW(9wvVTEyL{b8(uyd?S^ zV}ow{lQcy&f8c@902egOhct{A1q=%6TVZqG2YO`@>sWeVV;hiaMCj6(^U&T@-3z^5 zk-V|5x`z8ZT`GDTvmTCY-Vb$1Wc?q+c*p${H~}7^qVoP6Ah2eSQo| z0EU$?r5tJ>zgVcz%!43uoqLZxer9aXLz>ZAoU5O2FPc4ZRSr)p!|HfeEhNVPUVh?v zch#N2h&@wSADiop)EuI@it@Q6socfM74+ANMj%)v-jnc_axV zHyU%p4G^PPeS^_zA=bj?K}lIQ5foKue%tp_`x**#GNq`v>jg^(BcuseK@}h6ljm3z z0uPBErVrXLX|dy!MK|BJUrAHUkF`5iO#etp;VjQH8YtGkm_N(EH9o9ENnCYGG|}B2 zQ~0iEoea9hkoL1e6nstkMN7O)UG}5&7V%ZSnvoT?ue6&r?NXdsB3jD7XnMx+YSc|r zvHUgp7FC-cRdcxP3G=`DL$vT?BNT9yto(Mq%{y9|_sF12Y6$!R?*CPjdLkc#bGFa1 zzv?7T-aTN5k>Z+gaH!pMid^LQyETL&>eG9SIf|T|s$nlSltN#{ zb03LZ=q4}qSBW&SQF79c&CfI>Rj=9&Aq}ARz$?d1Mf@2-RT4Lc%i*XTai|y{3D(j( zq#+()J{X~C;BD2ekZ2kMTAfQCSZvql7yilYt1-K_<_Bf`!ai}VdP3og{9BJaY+0yk zIkCU?z5VpCvUP2E(Y){E-OYS>xpAM{fl9jcJ@H#bp|7F(lG<}2Gn)YhYFbrNo49plEFM*~(R%DCVjPJ$%vdUSM&$kt9**8)=ZhXF2pYZ=S#xXws#c@O*xQoCDy2bqVhH9jJ=4?7yBMc5h7{I!ab@xvktz#hq++_3ZrQP*PyA4@~JW_g_ zSXv^$%VJx3F)Ryt(dlM8Ds1ijSzlX{GQoQbC4gMuX%tNo(K}773&jjTwvI8_P4xxX zo>|lSV(wL>f-$B|zK_G4PkpXLW9BD%9UK!`4g)4kVv!T(i9IJ7+${mLlNJDW&dmIC zb~Seq4p1_s3PK0zeBglFG5@$)ajVus`tBpU3t1 zM0bHXbwpC}X8XVp)yP(Tr&gpD_Z2&N?W`o*9NA1~-WL+GVq8XHY2k-6_}uP}7l=W1 zGj5krkXS@i=*MwuwNQlXQx{0j8FjIP`h~Uf;>^9JnT|q@ppaJE@D2F>ndeo_}QB~L}SO7+V`M)s7se3!gKtUbCC|#y4zZpA9pvnAsp8+d$um% zuWc61o8@)1?XPg3F;|+e+CD|@PLl;agd!B;zCNrTU~WWS3=t^IMh;>Ak{!8XMY_k9 zz#jGo&_9>k@6$(4_Zq=(s|8Pe_~Ii(Y2`5fQ=0WpdsZaQhS${u711kf?ogEV@6@l& z{Rfcc+dJ{~r2E3m^xOg2`JbCt#P7qXB~CA21xlRWF-*WR*G>P)vaWX@-y!0ev?UU^ z1zaDS++8)K8d3mJ^>-&o+Pp)TRp9&$HfiP;^kKaOz2#mm_%!aY=Dpe03zbRAQ(z z>TJ$WSebc4=ikwsA-Nlma;SYbbl!4-= z9+A!#-1>v2^lJbK<57qN=uch@CJN*ORc8U)&%ehbrlA!vaf^L}Y(slREL27zPfj{k ztqSX&Vd0M1cOEm{Jy{IXJiX~Gcp#i7y;xLzEIzLmm)I>`$NU>X-7sEO_{ch z55zSw-hN}gSXjPIN&6D#5i`E$ovsRn8$y5XdzV&E ztSx>&*#XVBX&8@(w-0ia2TGc2ROi^a(J%h^vW#_WQ60^zXSw&oBP~E(iX)d|sIdHS z7ZggPSDhaq#M5OwJ9V$77SF#v#i=8}f+GsRh@*eIjU_Y)e)wD_EZWiYa4H`--bCZx zu=;3v`+E~s-+tKk>P7*Rx-hZ0<0oGxI8R)ELB4unIcplm?~8oAeV2B0FsBm5GmfuLHk%A~lKVX+3_6{z_p=M5i@QJu>aCb?vG8pC=_e(LT({Cid^4T z`w?vIufQOKPs8HT=b8nHDJ6LB>DTTlIV5lf2xY1f@OZWlCgnltiDY4l92ZVBEv9!3gR zOPt<_RCk{~NUsDA-70%OzB!cGyf5i^OumFYSZ)s}VjkU$p#5_G|0v#n^{)Su%%eTV z(HIs41R+CMx4H5PXf~ai>9Lz8f^&1!9z2M`cbf&KA&qNSB9@y9S)Cs*I?io@i@GA$ z-%0l80yk4GE)TDu%dUGlj`ky)&sv#=bpKw!+oA!l|A;BIZ){Z#ff_%l1@VhDiZ2`! z&i91eQp*60mvZ&=!IWS%+?Y2t1Ut1aCqXQ%tb%!Ouiw+~nsN}RxTG)c0%lIX;!dk5 zA()Vt2HC3u?CORz?B|8jOg*w>SLy3*`zhUCRpn5MqE$>l_09wglj*S2GtKbqT4etM zdHKoxjlGWUQ!XyKF*fJs*D2c#s}*38et^jO*PDuvE^L3BRzi-c!jo^8X`A5~?|?OK ziw9>v7|QfYASM?2rC)rLxiniL12UJ|!isA)!>G|N&Bs^lu?wb*wk!h8roc|EXAucE zCIfLv7<R?>b5#OI@4UzEM|B! z=&dj-?JYV_cdhl69oJ;Gh-jwKAMj$bw!HJB|Gv@QUo;s;?$PUd^VWdOj8+8mj ze*=~Ys({DXi@(Z7W}YbT_P(~*tfs~I?$!Q_Z$!C=tF?f}ll`b2f&H&w-0DDlg0siR z{Z4GCg=WfQ;5%)1clWp?K0a>g7p^iY8q*(1iJ#(|m>4eeL))tk+SZy`^D3g)aLpuD zfY)qt<9uK~1q;{QgWSKllfv6aj{y^{&2XPYK4=wZvvWn&(MtQ}lFDJ{#C<^g-5oQL zEvJ6mNBuNYJN@_enBn_LrPjQM>>P=vM1=H1K6Nk^GP`?<^{Cd6d`U~)^nuLP#2O@6 zVQZLa<7`-^`i0Tm@W{zLNj$5wqvL!;EoBNkN-iuu6b;_l#$~hR+Gn4-&RqW*&DM~U zzZh`$D*_mN`EJq)u3xPrzP3?santZzC3`^gYx%n7+V>zUl$IZi)i7XS`#0kktH9?9 zwEuH58&z)n zdZcuMhdsCd8IN9ddqK4$z|Xx+LyOesy$xf-7+A{fF+=h?j-o~cnt49C`+h)9I%GfB z)(`CsTuN;^>r(2Rho!=hyMLaI+>Ty+9w^9V*^7K=_TFP!2=(jEF{HuW5N1AV$*B2D z7*8DZf6p9UP{Z((sb})Cqv3;`#QQI~ItY((?ipetxamT#x$kI0QGL$h#N*h#*OEeX zSA5w-Ec+`VAwYKRC3K(XmJs}k4_t4$FwDHgH|GMkLBG*+tc@(wU3`@-2Zjx6b` zu!)(5{c@nv7~&euo06)#3~>`r7O|*M!ND)Z2-jkJS<^@~$hz&C?XImlIjZ0!{6x&+ z;OS#IOOToPw3*&15gVgmsA>f3e`f)pVRdy5%-Pvo+s2~mZg+$|yWWvdf{8w8T__@} zsUqzbw)DE)Q&8$Jw#o-dYYRZg3ViM2gD%f7kV$=BB^s?)!lC)yDm z%HvTRD3$H2aS_g}}=$D>OM5{I0W;Z@|;g;_? ze~g8=O+7BiZBuG=V}8_}7nHPnLGLY7wRL0ZU8-O~Ma4*yd|kg@XQPNsI$ZM`Q^R+z zHOXS3Er-`v?SmEsv*sWujIW{)?=)RRh!eS2rezs`qLnmf=XS=!YUw6yHi42)8oZS( zVxs_Uxx-#-0IqtIOBQm+NE4nQKnI8?EdA;`!_KU;p+{2 z+Yl~DU6-Dua0xgtSNqDwQ`^ZX(qmwA;;R!6@tQ;{eD8aZO*GmlV;g8=V*dzd$r$zO>RM&=iR)=^Gdm!7Z3+MeJu@=X{Cr z4K%VpFLYhp&$3<49&C?We}-RQ&4$=?2swOqAOi>y7H|C|3zUfad?ioDM^U44KM~M# zFU#FU$@U%{JE&-=UQf`PgB-J4tTZ#ZqvV?HraOH~@iTO<+WDTWs=N1GyX66Q&Uo!+ zZ^HSW>`HmnIOy>nww+%LXew{rc=aEoV$%ivgH`%bY*TTZ)1Z&^qYM&7XU7z-A zvzn87wgs{pUu^Cul(d@2fFsg&Q4AZmG{uT+>@e(nZhy-$pKEkIl?7muWUE>QNF<#v zlvk5@twYAirtv{mJ92kR4BOaNUkv}&>isgc&hfL*Us|b>U!8rN^RyXM)YbV&yIdMQ z6_bDq?d>v`RIxuzlkjT7SS_t(o$-5{#cgeEDc#=KVO!mgVHrgC2)(2om4D~GtI*hP z>C4URs?EjGmd}du=?tm&OV)BW^ljO)V5n%jt)1^(6JN<79-D`~7;E%YQQd2O4?*is zzJjE`ewk*7GrY|5sG|d1fVXP7xCgkTK5$9WvX&Dk;@W^rdllYWYlefo>LhCKaYAfU z6l-L5M(%nrhRON#@WIpNp!qyzWGfyT;qM8mAppbUd*5a8>_#N!V4ASF<^wo5Ikg6h z-KXPB=o2ixnA!98JZ1;W+0y=sD~qf<2wx}jZRFDVPnRv)ItW(mHWLqoqb2z>r*%5(C8!p6vIOuih| z2L~96nyhCK{Y;Juj1!6bg~=t(cz!NI@LR1i=CTFdO3@*01xQsFlUEtOs!?c|XToPX z+XrMbL$`f39{8B>vnOcAn^t=X0;~b(@oVUP^1#{yj+m~eI%~X*p%A%`PaCy{<%7w* zt%$SI=S0uLdXd`Y3X{j}+6{ zY$(FmjxrZAWEv?QDZPVjN*(G=KMFRb#W|Hs$L5s6l3%qlwq`zhZXpaZNW`R+mjxj!-&cdUm=vkG0#9?Bhx)qx z4LlBQxvA8)QZOSK5`Jap+!0L_Tk(mg6B%^Ua9kGIi36UAlO(F-*j}_^*|;0y`aJ=T z-J}walw&*zz)^V#rP07m^n056oc_ghop0X$X>y%tC_B7O^9tu97in9eA3AwxDULpQ z!2b|?VCc$aGjrP$$JtZJ6q6v@iiM7%Vu?MTONZ+(V6#vfU@{6r;%#!7kfp?jfTfjm zKk0;v7L-aeIeg_Kv&e^-Ja_QcE88EP-E#!J?JYce3uQXW6W>p&X(slz=L1AjUCfNk zR#Fvp^qzp~mB6?w?66%)W06(s_V$#u13TfXG! z;Yjk4CMvDLcg-}?#EfT_=RK{hOZ1fL`S8yeDA@l9hKkFsZlxfOJN(8j!TkDQtjvdjA2vo)a;Lj?A?l>nDGy>@3wSKqq%gH!F>V`_%rdW z0L!e}m(;iW1_7!VBU0RQI0lCLl`0)z*4yC|+{TZ^?rj{CHC}bJag14pg2-UuFJxwf z40K+N4ofvM6fWEnj#8#yvpsIEc}?%UFmKpj%~ZtXzc*<};lu*YqyGjCQ=DreJpg*+ zn0E?$ihzUtCgBUd8kHdPXh?rQV~jEpf~ALf?>nxY!${jy-HPigw_NCZ3 zGOyYe@FPy+U)>3BnfPcQ*MmC0A3SKjiiiar^CRA+X|I2&GaYA42shFH4!$FqQLs4~;%nBs2OoM{LDMJsm})CW2|I>qw-%x+c93? zZsaY3)9H1F>F0mghZq0~LTfl9HgP0Lg7Tz@<|)AqXYbu*ON+HCaP5J5d8-<1dTGsR zmQ+1m9eVS9FP+@r*U~v+yi#02&*FzBiE9=aKRsh&)<}jM2tboEV*M(iHHV#WP+s+q z9^>~WtU)dgcY6mmiOl3q-?qs+afQAf;)BjWABrf-Avq{*=7;ArmhCzJlch5O^tqO31dUW&QX>QdSm= zwD*$UxCX>I?M-YskIIaiWW~lEV$le`zQ(j;Gr+$Z>S%ke`*fM&m2@M|rPK`L<+lj) zdX9I1dMjlsT{lb5b?9j3vxwmu>CDA%mqMH0;sOLKSry&L5AA7ET#9VH#uNOwkI0<5PQY|SNxGvoJwR*i2j<`vR}{ut=!Y&awtPJdwl%+xnkQ?4>rhT48K zG7=`7?cqTyhbB0%1$QZC36>iA$lI5{ZG202<^vn(JYElE);4lq4gfrbtFo$;Im}@` zv4tXNlycT#@8qKk7LMP&2Msyh zma92cc%mIaD4Ytk`%}E(YCL{w9BqEyAb}emNTFx1M@O3v)eUhF7e$>=>4dlK^YLKr>$5ckM3JO}IVhGS|iDC_!K_x zllm0@dF5AYkd5JsA)Wy(5ofMhkXBzDMLmPQis)@|>i(Hp6Eko&TUFdpC^swlwz*cc zrx?L!uf4&_7>S|sB6P8lM3U{r-?YH1VG)279@z~cC{yi;Xw179K%0Amz+fMq2fg-* zoTLs5j;*G=N%E7AOl?BK=E_`M(Gy~ z`atPCJrNQk=ACyU~apV zML;OKXm-*eN%V)@2%w+E{C%|DmSAkJc$WVM%_KlHhJ!dZC(69)&+G*uICI`HuURqQ zQrWsZ$PAlo9d|LBWRxAxWj#3bSd*lv!i<`y{Qcc<6mFQWyNXqnezQ#c9@#*JSiTqo zEjpHnzf0J|@u4?u^G~x8+<9TUe^cnF)m3vQY7S#~pX#FX^^v8*ys|@nNRN3OTciBX z`iP)RV_nTTt9VC&0gV?~AH82`6nD2g8f|=osE@2OAarKG;R$I-Rpd=MED3Aj<7eTf z*KW-V=Gm&G`iG;A5jvVTJAt8j#YYhz8{IHXMB8f+KO72dYqN{tt5OZG_D1~{mx#8B zh?Jj4IGmAOP#HV1Mz{Y`#_89U(4?FS&%sm1F?&vAD9MXIPd8`o%IOB2;dObOCB)Kf zt>p0dytq{FV3gy4hd&AoS|4o+qXM}RuOG6rhVT=$rG&U?VVLKbkA&z4JN2%N=?lo| z>z9v9W1YF52feqFiHXL?oviN25uYoy$#oZF+Lmy8yBadQwrkkVKD+iH-}1Pz)#BXs zd|a^4kN7|$>{fa0LA~XX^gtr)G)QpE55b;?hOf}W0z>EiOY0JEfukkUiTeB~|0T$4 z?$L;~%T?u5-%lozNAiuY*SOf7`0Dt8(0tyIT|qWn`(>e&ZWR^YZLT#ZTMe^*Xm<@X zcS_9I>c`e=4Rej+r^#=ne_j0^iN-%Mc?3fXbv5drH3^v%YE5Y9f>z3A-e_h+WtMVL zC7tjIm!XNW^ifbL!_J=&Xe9otS2=+2nj!X_C$4V;tLwcK0qh2LJf5s%KQ+uUA$7Vf zGC&2KZ!L6T?VL`waQH7U^?PI1nDzwq`l41km`ywQ*+;dC zy!@JvE5=)xj*vx;OYug{T@Q3>*MYbsrDSe{!Up&tRrE&*SgXImptw#jyl!)iE?-G} z`ujH=cBlMMPPR8Gf2XYBGy8565^wB{3>|SLUut^l{sq2R|G1j+{7vYx8{49Vj+{LF zto`n*CZoV<8EBfnxv{KHFe`!7<>lM+T`9PYE!*!JQiEQ-vLhn(7tDWVt_?ajpwknm5SWSv@|C_4d z1?EXPJdHef^|vn+R1tlr!;X_;QmMLTdGMQpwO~<{VBQL{r>_)(|$k z==Jw&TmtP115W)WM=gX^GzoW=4VOai;i9Z5%W%EbvK`npLJajh#VPQVFhk_ z^io`h5yo=3VGKjpMD6>*zo#cB=@^I9cy{+O>*Yrqdp;&v z1xAuztj}~0=T$BYRp|crL#OO7x)J#ivfkgW83Vs+qfWdght`QF)ig)^RiBT9k-*12 zXVKK%8XI+EHmV9A>p7KF$?U88^NY}h|7;Qw}+@zx1WhHCuGyd*$Ts=)NzAS6Z$!}c7m1xRdLqe z-s~PKsjB(!wm;6&Ja!niahPylja)Vz%!fai90@MP<6f>mqoDqm{;InB&OKWm2 zDvw(mzz;u6U&V-aYdrkSK1st}4eog<%z@@mxQ9E()g)fx*=EQmG&%I+F0_`*1U=7B z)~!)18!^bO5wxV$>)6`H_^5&R?3wq>5j~V9ALka3;-pdZyFjns@oJ)v4n!3;l&MVV z96DQ!E5z;rC!Rf&#KigZp{Q7!h8GJ1dV{a?%+%4e)G8WSzo?f5fz3y-(g5Sz0pD@p zR5PIF0U=uP3E&UYDorPn(Mx49w?w~_LoVqmW0r6rDF-um@>i(It5R#jWr5bmAv83K z9vDlaTRMg;bh#(Z!c+#zb9AQf-H9<9bXOXD6}OFJ5*; zW0KL}|HS*Y2q4hhP{L%xADP1d0ibx2GbH1P(-Hh6=jadj^X6umcymye^^bs2aal_@ zffwH?cFi5<@NlT3H|2eOqsf!Fk7D?^5{BVVc+D5TEHwE?H@r_-h^DTGo5+q{i3Jkn zxcs5YWY(qN(J`{WD5pU-%TdJjb@`N{#NLZ>VzitF2C!OgretDg-X6Jq*G}V2#0VR8 zmv^@H7{t=_SJGzU+jP;+ZOl-FfMXCqb=<(Aj;RJ4D^JOXci3e74b`{RLeE!2l}-J9jtth(+r0 z4y+-0JG&>Kk{Gq0dfmK*=V>xW+JNQS+W8)WS>VWnOTn@;iTTMB*Mv2S!?>CQgPu}p ztW%zH>8t39IE**GUpSV07Nac_{Cr@>U! zq^Cp5Rw@(bMz*?8lz+~Ze?S_ZbRDp*(pY!jD_*JFzHzE$KHY4tDg7@SB>wFN?#ipm zoSI1qg>JlU(=}1{?1=ln<9)qXxa({&)!beG{_JoQ-JxLEiMS@7i?q4#G5%lk!2T3a z_-8B-Zarmsm<2>`kK!apsd!qwx^xm)a{?xJYdpTZi zs_oVV`b17nzANsjp*>PwuKmVgRHjP@ZuP_hM;a#_nhVIsF*WE?TkHij@N6^Z6K^!6 z$|g;YONlqyVM>kz?p{taetC^?ysJ2JJ>u6_{98UG?5&i=N$;WtwAiQkPvU!X@GIQO z(gKW8TkOF-$$%-xQa@i`UzI9xu;zSs;hUyFY;6rg>)$HsAd%IRixI1l+v)&jD3?Yi zAleR7G3>Pz&X6-Vkb)nrVY{jj_z~dTwqsRDO;{~9s(Jzk3Tl0&X8{cjg z17?2;;Clv^|8d?&?x0=b-H*4r?F@`+S_T%gD})`YLu2XZ=fB7){4rV!WMvdOm!q3r z?Cd3sQU{Az|Jpl=BOj2p9KLFaDQ8KEfGrfGbG>$UPd?c2$35AT>KGoUPL$ioa&)8v z?S!4b&Ew$sehS#cA#H!6TuT(z8+n*#A2?f$4I|rNkmb0T>RIZyS@&Ys23m7bkmo7a z9$?sprYzUQYtXNLG)yHUJ9)2 zg$5lKLFdb4e^1H;cN}vISxDv2eP<%tLSoi!*u#dDA+c%G7GY+26kplRzVz~yKP)8m zmS5jo1ZyBQNPF+Ljp{z@+U}_vJY}XBsqwv{ne`?|k!P>gYiQ(T+D+LuM+B)?6G<;U zJj@#7V;*RCyiab*Of%_{Q2}1A0!b=9Y4!0ysY{)R!3TdLDvemSg)dA@7WLUsBxBHJh@RKC^sEnLA;Dk+P8y?es+dDOS=LB>re7_!*&JL5(q}NDFNK1h@w_FR_>ID@y`-vsRy-Qs}9gWM<&1>LttQG-jhxeu8Ra=^~k12p=c3Zv$HaopF{aH z>R7X0v$%clmxOD5h_@!M!)h!gWMY|q)`}`qeq2XdJiK8BUKOkuVJhIn+!GbxkIXux z4j5N`JGfB#x~)0LQ?HcR-Fn9B{kI77WR>d>1H(~4uccTh`Gj6`oq710!hpT|VROPc zhHtZ_bzp=mz$4A?V5@pq`JfFsf+F=J*U(>E z)8C)|dM9Ew(i*!oH`*V~kpY|2rz!UZP%y2ghn7eykySL!5w`g^NLXKXmGw>wOFE#hLl@rGw_W18k9^o2;|6m}j zd@GOiDB9o)FX z5NQJUt9(he57*qy^4q!{<(Gt<=Ump@hi8m-xbnNNsO(MsULU*)zkchI#S#zE4b1KbNX)%o)p%x2^k@GP^mebrLti7*X6e-=*uB8Ds6;a(1; zbm-Ok?<@d*{TSourV?2Jivz#2yp99?*hyJt4v#~jZ5ceFkDe+YUn)+Ix=>WZ48E&# znwJTxqY)Mp0am1sq+JVXqIc;3vh00tDlJyyAF;7~gFDi}Itlak+Uc!(7U|o_0r7ag z&J}py$!kALEolOfWl?()Xp1R^K|hU}dV`nhlt_^}_gP5>Uv7n@sLrp0-T1Ddp$E%@ zYCoH7zm<)?+N;4ecDUs6LH=ZVJ$`Vul4|oul2X#i39k2XnDs`uasWB;)h$#^tZP-v zKon;WOQz1GmP&o5K0?kxr1x4%@>4I0nuYR-e{^(ozW543%i@!A;}AEx*0n>+(;Lly zOa?%xylOLTV_Y$)qd86Tt-O!M6WgHm!0Xz#-VMk17RmAus z04KIAbhgfx)~@s?Fh#_aK*$+N5)%5MFGCu-ZONlfTXk{(j`bY zBGTP0r8JE6FoT33AV@buNO$)PA)QKhcQ?Z@!&(35JkNX1yUx14-0S|nKU~-T?X5Rp z^2~zsdm8?NUh_)!oTmz%)$Z<15birFx+~H|8*T(trOBXi@bw_&MJlr;F(fq&j5^D-$%!>X#_H? zN)HL#2{bp(o3Ru)*_xc^Ih|%I44Qv;;-B?#TjxF*`F+is^J`)5xf)q<=Lbsu@3OsC zlxsWy22k8Z*LeGA>G-Vjb>=sTg#y~d$Pb^i78*Fz)}>opB??S0w{MEE+^m8QEalBf zz7wQ=Q_G~R47R5q-_^f9kg2n~UMwl*Eiq9Pqc1b~o!1gkLi4+o)(Z*sF(bBnokQcC zgRd2HZb(4I%PPkVJM9r3Ebc{hOY7gE}ZH_+4yfy|nO-i!!q8pDxLUt5WMG zbfa&4u(hG8`^GPJ>8hY=a5eBiL93Wbm7;X^-h7%iz`WxG!bPLnsPFG>23jgCairv@ zba_5J3jAnyVy8>{_VL_{36*%28-0u3=zlgRFFMQe{ptf>IKxFF%*>2 zP;EFOo*X*kF9oKJXVN81FKX{Xc7)Y4M~f0i9&jWXLSJGtioZApA6$G7+JitRM^l)@vjI{T27nvAJZ1Y?)l0TG~=*VUANbeo(x%(BJ z)AoJ6GThwWT6%|pv2tK48jVcDc~K4HF)LEhHQA_*Wlz{g$pJiYL-S?{IZX(LWLmgUAo{exO?KR;c>C8 zACoH5p)anjB&y3B2XIQkSw3ptMjN+LSpy2{T=tBqtJ^mtyA^vv?_%7RJlO?}>QJSG|MtJjBGwccr6^ z^Cr5+i&c&j&Vx#rC4(&=^wBPyyNVlZV&S{a5w_3*u=6mIg9$xy`)v&N|1uP*)cWE} zDwYsFXE4$vUYgvw4CqqHKeKW*H^INnfiTJo;5%9J!EJovm+IuW13y3Lo;RRJA7fcg z-I$oglZJ-+N*w!{^d3B+Bft?{zdpiJ7Nz>8sa)oZ)S;dRkUCHF^xHIICpi)aoby-$@a z_W#BKIe0kZyYuA3nwKM#DQa>Z>-~3mbzSZcn6}a;Zth7e`Iy>wY>0?lfFVtaY!8Bq z_R``4j7C1mlZjW2z99#;GmFfH#<-?3-)X7QA*VGREm|Q+H$n?Si5K9Q!N8{|+xc47 zT8~ZtFQMDMRMKol_LhzzS>iTQmCpm802a9a5h^@2de-wM-R3>DM^3bvp6uBnkc--R ziDX4_ZudA1xGwVYa{09dW_D^a>k z4OknYUtF2Va!*+#)2OQqT{G6o1j$G;?lMRp9QZh*Z{HmO-}g1|$P?VWGJj%~yr3PO z5{!klY74hsZDqW;_v_zLqQloqJ(S#Xo@-ENSiYXrxtJYiu3{2uG{N@g7yltKO@3FpLK(f8PZ zD%7``^5`X_HHP5QA(gu4Ke*0+Yq83Xk=cXwffc8536WO%FgiAj_3-o6ty|3YL)e7~ z$(fIiZEI$xSL3!+uRi28TdC~Fii~NDHx5;)HZJoPIT+DWplD&y{t*~4UZxW9<*Yx^ zml4aK&LMb_UC$5ah2E3N)@1j-UF`pYRDf6z6!Bbg$y=UP_YB; zz#8i~=3kL-39pa-{fwTwAk65VD9=HvxoglAA6O)Y%v2O|3+caR!f}3BJhD+wQ}eo< zG7h^)%UEUo(i5Z`ir{7AugEFEbNy1DvUm!WYjiCEPT*+ag44zKX*x$DN(r5;m(vRx z8x455iYezU*j|2-gXFf~q78?Qcg@&IWPD+g*MCm?IbEmoyeX=kwTL21DfZ~NKe?Ld z@{s3@in&%!%}yVz8d{*q{Px58ZU5%&js}ZJsrG56{+?-Z#@<>98;l=Pzi<>&m1De;g^LyX&ai0+C8I$?C^p>*U_C5+F8u^>w-!vgwrX{{;{+dzd)`4lSV8suEy-$>-dt%C0wN;#JUr831IE8T5RJ#ISGFwqhq*ES;KXtQ& z8S4aiuv6<&Y_nLNTfvSNIu_+UQ&BiL2bK@v&_rTB|F+|vE~or(Knpz=y&F4M7rWf+ zZ;ibxp6;mjmeK)-#r%_%4}s8vk`fzrLbZ43p(HNb<5vAW*wfPV0*1?#?|3e!()Bgt z4K98zpx*>72_-YriqA_W-?$6AkDaGv<>6?IqRNORCM@cW3iD>1fB(G^wczXI-W4zr zB(FY@C#}Z@@=#8P&W3iB`p+)?O=d~+GPH{IeC`Z_Nt3)iE`GtsMS>v4eH$~{4-X6| zX!Xw!0ziDMYKUF3c#0Z0yjwa$qu4(0JJ;lmiuWhZ_tQ0dT}BIs@VpjisOxZx!LyG# z^{qP9zfm;5Tc_-S)Vx1ftEq8bWD${A_$gLs+&+5|KsF}W?e}3%WZj?T|IfJblhC6j zbEqcTwa#u{_!}@;g!}Fdx!e+U&N~Qf2_s3@1x=S1JKe(!0=n^$MP2F zr4{-KfPQd1Zs|EY^qjAWn>wgkmN&wTv$w^LFf4oLye$D&}=1pU~M>h5{Q&fS)K zbmU-Rz0i$ya+mR(amn$-EKxHz8jDJzN7yJ~Pwig#+gH3HIio+d#n0ncy^x=zXf_Q> zpmpFS<2ONUFO!<0w;SJLq=hpj<`P&Kw~GzrXe55 zIsH^(b#1|C%0=}INxH_xG#z}qQ|Y-wop&zDwS(d{V>s?i9hk|tUoP~*bTV>Omaw=M zTC=8!S_p>PlgcsWt<1mW!d{H?>8e_Gzv*)V2<(NZB$J-pk!!}QAI<^_y_7+dj4r4D z{&{X;c>djMlZm~JuUvcr*!owQ?vXDgn9C_=%CzDjSq#><%L_RuIZ(tL-=(-^DoC=) zH9cb8mT+n%^28^^Kyc{Jzt#oXYb<+c?T@7jgb!#pRt0MBsBxumY^vIt`PGyLiZoK? zt!mIhEdZ($)tVEpyB9Tb(K+*(x|`(BPMxe2K;)X@Vq2Is-?DsH6xcIq4TDL z(QOypCDNey^nCgHaCWeEyK3NM*^5Y6RaM3A-)|10p0XMvYo4Q3LgfUTzN38OLiVZl z5o&V+$`($rR~OzT095n-wRQN&t)FCRz43J)Mql>@=*VK7&g0P`yV~3EXKYP|ymh_v88q^EytLiIXYvHiefpWHW z2@6)|QCHY$`C?e+lD!SXSWyqU$^B7a$&L7y&PDvm<$8vV^utX>(?It34$onpRa%g= z*Qw@7vKO83fQTFV#_5CvcK@e;`>1X#(MiT1or?Lojp9r3vAox4Ims8HpT0&NH!X8U zSsK40k-R!1yB+7cGD>L$1yA)_4PM$6j{4rr?{0UkN`m#akxuB2W(F6y?_j)$dSDOu zCPfNXgp2ELBt~YSL608#QN6()ox$(g-AwrZ@vi(N?QlO?%1!`659pu>82j}ok^vBv zp(9$0*v8;KjB>>emc(7!*`L>Fy!)J-7pkmxMHWixU*Fisp*0dlG}jZokkwG@ee4(# z<0#=26#nZI=_1z@bE8%>Fk(|$#ESz&4tmtCNsOX#_-|c;YWZSfa2F+ z7kk*WUV~$$(Uwox&r3j%Esk)rSe%*I^-^>Db-bXhEva{7iHa4#P=0NiZe}nG0RhhR zYMlaU`aC`D9`3$;uKilF0)H{nI?B$H)LHIxvGZ(G0(9f?FT$*|{PB;nu3g{Ayw>?x zLj1;afw=z=S(6Vc~d8IDoZ7#Am1GP ze}LC^Ispsmyra@*-X+Lqm0Cv9mHCGwpf zdvWq>JfAJ!h@33K$9pRd^(e8t53&A!*xaWUY<`hmU>Vy3z9Yd3sv!qAQazvlxP ztx4_)QTzu72e$jQhPM4NJf*Eg9p|Cv3BOAnCCdx{uAXO^(>$65O)RW@hc6X4nkBCU>rz&gT(poJV=7@N%*O^k(;&a^g#J#BKJ0gPEl-0pD(c1r=h$+E;he`!;X98tVmp3AS%m!7-1_(gZVP_=MgP;VgfUn3npZXH`9ft zNcYdKT}_f*&GiS4OqmY&Wf3WY6u}>h@fyu1&W3()baHyy=dTUSZgQIku*GU1QR9Jf zRNQ8^?xNe5EPm*2kmlxtL#7(c>nQcu?S5l-JAny-3A%lp!?Ym!8KGwIed}wo#9dVp zsGPJ%&-KN{u<8;0gh5A)UuALmul>owp~$4Nt~$ z)+f5ONoDFeRk#a$vWxH5dWntoS4~#BlV|iX1DhtS9Wfu&Sr3V!&;dRHn9(Nqeu0}A zfGdm}H-uiv$W)TXat+#4JKo$3gbJan)utahwKfz1AES&o)G=EzKhbo_o7Pwe z5c^yX zG(`J^V@>F4W)c#BGu2>5tg-NBm29&{)9H2`OxheZi0$@ON|mvU?ibeyKFSRwothpu zxq%=Yqw^Cz$Y(Y1)0Rca9qznbqka!q?jO^wM77+5P^A}dkz>%+ifxAniX3qX+a2CF z!nUh#WbO7Px9o&o@QsEYPu)91^*72QvxWcGUl(4BCt`wHRH+cJon|V74-mQ+q?$WO z9-cB;jV(_eHlAE3$3`cZgR3Q$Y0R~M@#n+aDTTO|jAp8HgMG0ec&|~hmX6uMQB+Mt z$hO?$1{P_I818JbU{YtM&BLo$wN9fki32KGR{mWsk-kyk<3FEe8#c?^ zq#qHkF_bG4ipeSK?(rqqeEFXg+E)>V9fC659r=5q-meX$g-Pgk@qWBHo|*YlHmvNexfo>M5EYOkIpzOb0Qu~ zxS^pD3xL@3MC)9u5@0p2Q}{~Dur9_TIqCrJ@s5fp_`=)GW`V7w<)^4kFDFBB0{Luf z6=}OroJL>!7X*fC#?Jk!oF{5s1L$+nP-#6M9f5({_J6b36jdq)QN~4kg8a_zsr*Aj zpNDKtGEn)HLYoR!rJa4oBPI}i_AsD3VG`k->qGaxW10jGCHrws8on>7A4my+ga3K@ z=7P)fl!ea*X7_IuuGy!r1|+D&;b)pKqB+|#8+aw!n*(>?Gzy6vAVU>E6C@B&F1>{c z&q*0f8Te76=`&<C#k1u|>NFYlc+`LKFc~|P=pn!^cdG&lpq}bV^XyZu+j`L5RhFcR3(q#; zaB^xjgQ+M^7|Y7`0D-ABB;LRv)W>sUEb*1%QH{8zQR#DyF=mP zA*qks&9Y4N!GSlvM`ff#R>%DsxMloCAPUng(HqYig0LW%-6hpIw;;9OR`2Ck$cDmU z$e9k$NElZ@T)$6GpO=m$g4|%22J{TFX!TZ9wLuU?_^ql60W=2*YO&UYR2Y1`QPAZV zjG>a@s>1KI$U53pQ0$%41L>olZGOstUjJJM zb7b;;zwC8~-_edy_n?dTp%|t+^cj&Ai68nDNZC0qiOMts|25r$!5{Sf05=0l_W^!m z^A3X~(6d0~{`jdnd!X*=IK3JW{QB07psWMy?jwBs!XLLfd^8-@!GdEyAJYhjx?HkR zcE-vpXH}!0-A-a_-dR3K2?CDBmvyVY=o*TLk0)?_J)#wFe}?X{%m~N)=LAjipD0X- zJ7#VC*?+zGndtYyL2&sqRZ<0lOa|PoCm($pVBN%PV*uHy?;EM>=yuH?cUB!zaj6} zObHgHD6K9qM|g*o#!<3=dX%;&6x!Mel@FS83%uoR*$2V&qSnYYr49nmoqWi{&jOHkQHQ*{5U7$$TwH<9PpMjV6Z{Gw*O{-N-24)0Dwg# zJz}xpykxFI9Jd*JrOLJjRd;zu(V(78O>Hno&-b7ttNN~byh>G3AgNJ(^k?l8 z?|-8eJVyN1LuSc7G}~M}9Dn`7WT!*)^-U#|u*N7uhx7;nP@m}*@rI>UINSe+1t2Dl zs;@c@;ki%dp`$eMQRtEkQe=Ywf0*PrB?`vKj*B@^Ep7{1cWrpyo_BPdgq_&MXFk^BRzIV1I&3dw!wG zrJ9q>lm9rZYaho+o(UpeLxkj^L}-qyqCf5gmxrmkS%`tv3~E>a9?_Z!dr(}Fh#lq? z0JFXj$56<9azv^XL&@MjSh@H%Y4u#+GL52`VXz~eVZN0sIm46|g!0lqINB3|Sq-8>~_}ckxJ-xHU|fB*H$$-*A#6|2p^y)FF5xg6IPl zgU*kF;beL1CZ%aGUe_IeLuR-TQD&xR3Q~m-IvPK%7vU&%IOP?}(ym1OWtKib8{~S(IJVXd;8~w-bCv0vSQsv)4gF2!ajo5?_~4b+FKurTG4K?z z75;;!B~o+l++cH6SnN0&w3U=%kyr$K2nkuMbOCc&2b3zZ2pAzhv6XASp(bLk{Q1=D z?U#eEe#54G3EWeGJLPHVHa>KnTU>ln9K!|`iY*db&0p+1r`yI7F8;~y9~}Ml=d-lr zisday@}=-|(^e{lr#%WwY?LD?3t8p9KHoJ_pTjS{85tkPA6XQ+>2um}{i*(>KEa-$ zFP15`asS&8C}lYTbkh!&-W<8K9TTYgrR$f#ZG453V-`W>T8)X}AQG@%eg>FA}3JIqUbC|Nd- za=v1L?{s6|5Tgfvwg9=QKGMm}e<;rU;0I8jj0^BZIL5a8@af$)9C#`M{&3st(dD7| zaR@R5FLMOb=i?*8O2+i*KE=>I^b6mrkdVyG$NHRB&bA{mCUyz5FMl2SbcZUx{nBk~ z6h27{A*C8`b5Ce6>1UvcT@^@-02F&#cw@~x?ldULcPRsmW=0d!$kx1k;HGUYjy8kB-UEu zDHFvIqnymE@|&S)7BpI8L0w|*K`91Q>`Q;-yPF-@$PL~vn4QAxW=FYDe_CWI_Hk@G zdPMge?`mxa@OXebwx2Av4X4k}uRKz3rs@IM_^f*@|6jQBKR?h`f?tHpmK^JRl%2+8 z0Mc$teSm{%C1(&YC>Ic8xHVYNYpAO29cO|g=)=YXQx+gld^gV3MM+tyRat4$p^~0K zt80~k?MswN(4C4s*%`C5giDaO5KE0&vJ_72wNRuV9-Tz*0vId&t|`AbE)`9%V4p=T z(*AkN%1ikj3lp=f(B+*Op}7s+-GQL~$D zMHK$IBv$dvk`do(%c=3a_98bwZnDrHr;9%}IYcoZv1L(X3&(inl-vd08QOpy6=WyA z%o`u{+9FZcM>GwWyinDK`YV5*SUgltotKAlL5R_a(;~LM1IxxgHV4Z)4Kc43fwxX( zmA0|ouQXls3@TP%uA+MZ+W7C7Grd>NOc-CMuSco4qqUIm9`VGmp31DD8>mxbD8e0fLI{o=PXDY*`E>EP4-shD?D zh-<8k(^8rn8jN3F!@o-rHHu+$raS3(#pd1wZ%(E!T==34{^sx9DO>s36)Ar_MPv}! zpnYxBo*vvM^AC(*)^}M^f4CylU9ygDrHiVWdJ6G07>8vm9haAbsht!a;U!68GpRkk zbQjQ~((kvYOzU0|vj07u8LU`@Ys$FpLp|7Qra6u1SSZTSZ*}`LNpt1y%kOGnz2u0^ z{xEU1l}i~%Vv@lO~04V=a^0|O0RYe2K6f4FeXg!RNFA)+X&v{6&_93TS9Y6J| zQ(6Cy9=!DJOkz-I#}ePS*DniAra2?tHap%lC|n#2^%BALvOW@wET!Xo)LZ@(fGdLY z6Q|vH02*ndOZbshKtBRZ`l_U&tn~beD9VMve&lA})AvGfc+tr(n6T~xVDnBg=$_8` z+V5SBC4K_;Y4SGXYacrpr@R=I`QXVt3KNC z`jE=y7InDKW8J@rP~V@-ymR&!e~kU3{kN1>u($1~tZFaV9-$UbkM#Z~4NTvEbCTw4 zsYz{|t;~9N(GAjMubv&|JGL+6-U{JdzKA?Gp)Pd|@NWgWD8(%{X|4Fr2zVX|&0#(O zC*Ku*skPeo_jB!fyZ=Jo)so#_=HZ*qP;;&PAikEqQ5bsVaqs!O)+CXaOZK+$==)W< zmF2Gvb_`)dO(ZunCG>4YW%`j;vkxbiyKAe2wN1JDnDcP#Hio! zhYKIacW?^j-rK?yWo!cK8ykQ+TrXv|(Ab=&2&84xaLqt~8rPRqOG5A$P`S45Co!UT z!YjHN_H1e3VnNLp*ooppBb2HI@cJwsaS3P+ePAd zz^5y?jV^HV;um?f&VH0lb1#E)k(rUEsf7()0OJg2k&o>34j#!To^k&ETBUC3M-iEc zQ)58G)Ap=-!>a{|`K)bQi)3dBk;N!oC9;!;$=lOMSv1o~YHcCXuHj)5j?YRh_j!pl zCka|U-F)`@yH>OBV$;>_ zr>@KK1LR4Pp(SWwHI@mp_Dt+}N_YE@u7>IeA5Q0_{pbt9)um|3HrT`6Q$oA5xEmSV zlmTt)PBcz1{VgzFMm~(oPT}kkrj=K22{WK&G82+-*e$mlO42xp~FpnZsjkeaftOfN$ z^sr0w#?MLNH)2LexCbrgft9D~zz1T7qm0G|TRuIbi#TjA!IzQ2RQgwu+b66-eK$D5 zIKP*&x7oHf$I`}AQR_7{B+^2+d@o64sVNbR51h8W!Z@--Ilynmg_o<^th-qOSe>WU zJ2;F7b>PnW?~E_#lN&N-h8S*T*j~i*Nin!Qmy22Wv02C^xd?a3uNM|^YI*WH&f@2> znh1IlF(_CKv8eMeNKRosDSL#JJ*>r;77!-aNGDVVi=JRV!jgWNb!efVb;hJ4-RD0j zgqRbpO9!CsbTU(jy~?-WzuEHNnlGsJMbhqnd;d;^O;s8^En(O9hp1Ebk11tTu(%{& z+f4(@i~t8`gsN%)^|MrGmdQ`8OQjmd8N&Z~*v7Ki9kRbhk7S7%&$v{^!7$cY(OC3O zmLCB^-6PV+A&l8i6|_tC>crellY$^CV{V;9OJ=F+l*0Iq@^T7;WtTk|TE|E$FY@|i%zhu6f9y4lz2NJ| z@vb)8=rqAr`+k28c6P1m(xA86{!UL21RqfR7#r>kQ&Vj<(?9OTO0@SVbD35W@419} zMZ(tklmP#>cdI-ohNc}s{WG#?wm!N1A{4`PMxkm7&&>H~jh2}iH+i3?0WLpJOF(X8 zMMXujR6sQW@Opc0M|68`tNB%Z3|40;t57Z!2l z9}+f}A?)@?eZE7y@pH=x_SzDOooKH6C+FOHdZ+;49z3NUyUqwv5A9198$5@XWHOww zPI!s^A>Zr|46m6HZNUuZCZ)5@^D+Llw>SM8DBCZLa0r=b!~cCEQS(`D(;2nOxOoyBM7hXcZ{wXD`z5B4dA1NstCJo!oZ=|U`Tff{ZS1aswX&(5ZpuI5 zWWdbg=)Hq{sgb1S!lDT;{I>y4^a7cbRS6sbJ;khm0v>^9+ zlXIthshL7^(a39ZR^IXBZOzhZ`!RIO5`(7&%D$N3W3*LH}m6Z1T9J$8tz`@+Y zG7;fM4 zoxY`Pz>G!h6i#Q3Kg&DNAguT+vT{GuG;9-#p*m}2%Ari&IRh8EwD1xDGP$|gbvlV} zxXiUO^6}Tba00Dm{Q+O|BbG@kTIPL#7|>Z&^Ka7Rfl(b3VGVmG3CqF}Q4MNbNz4FW zL5npTmi)CKHOcSKVp7|nq!qYVgS;}9&Q1%@_fp}mlNJWz_XdPFyGcdKC@;Nqlk|#_ z@D}NqJlHC_$Fi6~RDTxo5=;NNo>^TLYH6N+oIV9o^WMP$-*b~E`6-=&4Yz)3B`BE#FzK?xHf8zUC5OY?!uE z2XRK2WSvWdX8n48((yX3&8>T62Ylnqc5HZkiv4HjK|AQ7$1l}%>OL#?m87@946P45 zHr#N1Vb#8>TxyKtCczb;Oj+IKJ4|=9%clE8ciZjPQu*%$Bm~(MY=!TAEQsCBID@kB z!)=te>oz~G+|lWDjUVth@=O%$E05h_n%&g#SjltT2VU)d{j^+*q(C2qcR^ay@cJ{Q})t_0M{je~U*E45h?^dMq*bKr!YRYYg#i z_#^cRi3D!7c@kdEc`AML)I7GB67W12T!b2AYeAq^SJ*)x0GCR)KQqkKe9GVaJ1n)umy$+?4CU3|m z{?)$l9uAVhQLrz_o5yId_?y*-1X01WUBF zfakOUCr%~%3z8h;f}FsfRzot0GTrW-nf3Sb#kUq7PnmauB%hHE`6tWuBCk#1Y$Aat zxtr`5>S23vk~qS-#gK8vkr1iZKLJ6;^YvdD1G0WK`+YYWOO;k|MfWj04?{PFr#Tiy z;}Yo&mr02)gxZ8|#zj$oPV4a8CNd6hM+DrQ%-pJ|s=PbptALeMf5r=1fxFZN`<#T^ z#3v8q4AZlvx6u$kf8|chOt9mW>_k&D&=o-Y%%Saw=dZS`xvl(w>N^3RLSuuSwv|?w z1m~4@V3fQ#x%o7<(TS>CyZCj}C|6iz*PCFE11 zi@TVP+m_~9YQ^dIRMcr(a*!?6JJM$H51_U&kB<(cvGq=~GGant@RYwwFzWB$zmd&N zDoidn%S&Cz8?9re6TYy+-9Nv{Pncf!DT_V^g0dgKAHqb~EI)Dv$rSEtKpxmYfYriN z6sE=z$z?Rxs&)xP-MZn~q6fTY4+4m-JTm>EFG~O#eX|Pl`;Nolv&*^=v^0WX0J&!q z%aJJkZ`F+?r@HntU=`efUaqN<9py3Bl$Pf{}R92 zw1X~N_wx7-Y_cwP6*a;4oNMYqrQpn2BvOH1o?c#tVDrE0JUgAz@vj*1F(p`{#Ag)D zk-`(oxctl-amKR!LwV1uf8kZE#C%rojm-ds19nO};rX(l8&iKz1B_{v$tj7Xe65j#FowHvGHAMAU2 zxE0_7)II{eFzSBwu?q)EEb8Y{a zwWNPhm~LLCktMF}=y-6JWbJpW2-;c#X=qa(r(d^ieN!@YIyrDIE}F-$M{7&V&#h$h zZn>?b*V?qneQdMEGAK1sABw{YG#ArT9`Xp|!PDAFo_RLx7Z|as7*ka@CTa@5AAc+e zG)O9#Yv8myk9D6}ZKU^(oI74@9OP1^R#-NzSmg`Z@OilVp<`i?s}e8Gtx;S#PlWrG zy{I+X+pSd~^Wia39 zl`kYL{CjCut=l}LdeDXEy?t6m&OF+}2$mB$!#&tQGZtg6#JzG!Ecvk1d#f&&nTe3( zZaR(b?Sn9WafFZ zcXRp^y6^wH_Ez*tGAB~Mie6nzbKx5(G89X68_l2N>JEmPBFDsK}^ogC8G zfd?Cvo(UrPr0_ZXl$`V8j;Le#d@7RG8lqx{B~PGB=faEu@Zh9u`fYq7SWoVyw!t~o6D~@MhoUcky(Xl+9XUR zZ<;7X91bf&es0>dr%>5+_2-8x2bX-L=+B|8Z*G1PIr)kMYj1RPQ~~++JhO~HUAEEQ zp`u=XTUpWJxUoUY`b6=>6zfO`%}Y79-RmK{Nz`(8F|OheAeh*3x6~UuGpZ?hK@4c8 z62l~3+TPcv)nb>$vgMNXaSef`CBrFE@c%n&EfQ~Qv=5&;DW7ri%vrb{vb^zVjEm8BFdrEg)2yx_T&+86GAYV87nKGx=#$0P zbe?}``@(rEVI|d3*GLQS6|}n2KrgLT<~Q-)P`zqu?F}bJuUuW@MY=?btJ(+7hFBL7 zcoX9}p9eL3xv+=P^=HZ~g9QuEor!(u5fwl?naAJV$M5|p&*;i`QqpwOT4vg;!1Ytov)BY?~RM%!aJ{|ED9+|Lk)meh1c_0uyGA22*R!lLI82cJ(`YP?6Yz zWE%cGLGEf5k9}7>FLB5Y(1O?yt%=#}?D8#N;Wh*rum?~eRzs%?0hk%G@mu`P9T`u_ z?kVE9{@XvuBGv;1I(y!^wu=L&nBw+&n;Vtwkm=ZKn6L|HrD`?7Y*yXHtS@hT2AlF!-d}+nK0odk09id{J%4Q z){MU9mjLDj&LCh(F=iBNZPc34Y6}np04PP~KJWl>z7vUBkR@<~lf@EQPY2pn+^G09 z$=9D&IDQHIUu?ZqP#bRaEt=pC#i3{^h2n+c4sB`i;!bdPD;9!NDA3|AZ7B}H-HStU zm!P2~1P=j%-1(h*{&UXUxi4$>_psmAo;_=?HSsWhmUJ;t;xy`n3ng>8CIH*6 zH{L(bX!P>;96SIvh4e2cW7#&W>FW!*{Q!Pxb~UN|6b*VwrTreEiCZ&nIF|P#N-Q+A z>odBn-&W4bMhPdwo(jpzGImbS$LgU@5yj9b+Tn=Be9ZAwDB(2cWX3v+wl7FMt%JOI zL{H||@zPdf`ZtWQg2vM&-|^rh5P8eT)}wAMyYHJ@Dhw4b_D1mKgM_J}5@PO3q(CD| zEM3xx1Ne~n`39yi^H%oj1{nvq3^V_sL6qEEcfdlSf!TQlxou0GvDQ{6vsYOS;lIGq z|49Bl)ccG{rG~G&1~|WlT{e~&19a5iPHcYyU+}QxWR@KmLFDpx_={I0`UrxA(o1m% zclSFJVEi;RyFV*B^;8oQUfU9l6%&1h?p5ZlD#4|@f*%2rVaf{+kS zx$Vm6P7fUUzJUogndy;w9wVo^AnBHuE4?CL?`2bipFr=*u3%3~y$$#~7OWv$2}2WU zn?Hwy;g0M|L#}K?g{S529o6)Mtt(?>n;;(f+V$^B*m~aEq%;C;wBA>Irb^8J>b+{U zvdQW7O-)czUo$J<%c}X~@n_L`UzBE(ngHJ$uw~khCxMaDfHS98U60Bb_A8q4aTS?L zrn}u^U9zD;vi9O~qnp1+hiMkSwfRTLi*ewXFwE%GNXI5h4lUd8-ayUcQX@$^Vt9W% zb8NM#wxT@~scURpa++D;%9CxXomssm=4|@z*`MQ;@?gSh$*Xc6`@EGFe%9vlb;%gl zCvUy`egke_4~K`H2Di03jhuA`qXkyJ)Ub3@j`A+6W*xL zxO`n2FajT=2cnr+xG#c#J#W72Ztoq~XJK74SkIi(;JR{yLEBc?pv=j`^*4i=8c67w zBw{lmsJW%-gLGAOBE4w=>{OZ+d|xr@<6p@`3+8uKC0gdy|}nQ{Q|P{AuZ9!4c;la z$1j(?^?E)BDN)>d8kqvU<#%^j(H)IiFR0HC4LM$1<@5wd0_63Mb=Xyf)ZVvIoeme% z;2K8hcit#9akmtciiESLSKzcp{UNg8PpIJWYq(+V9FCvH%RG(EXuvVr6Sk0?Xm|Q! zX(FjB8Gm2bSw&T6Do-`hQEANw5q#Q#BHackRyW9McaMi3)c3ZKc2bk!X9wsZ8Vol`#t9{nJVii{hEuf z?*@=o8;$$QNE}=E*|8pJFzle}sKnine@vc;&G8y2V;(^;T0FLdc@kl@#iG|tP(V(sGBF*+66DeE|M;OLPK(noDxQE z6Bp{8Hgud^JX8uJ??tvnuV!a9;~x5?5Ind6Op%#P9$sIvRTV(6B}!a%U=NYp2ELni z7&+E!=Ykz&Gp!3Y%g5xky`QOC3pT2 z2h3#yNzA4tP1VM9q;IDEqu}cqr%TGZJRh#J4Idlgm@rJPIhhP$K6f`VYfNELy?2H> zX5VdkioI%0__Rgf>j^D(PtDx1G#=O+STn1%?8`{hbKQ?LQe3$+$}1G z2_E0|F`q9c2&B;P8YnVg`jj^dVd3|maG|ir#KODQ^~=Gj@z>mu$#C@F1sb(sZrkKN z^m=8YlXB>Dm_y*h>Bs<)L+w4cb;ME>RK}wN3ni0s9#nEJUaSX46NY(o>?3BA(r5w{ z_3yVlz&_KTkhPxnfhYH)vciG!FCpam4@;)qLXXimCt-dMBDkL3oKcofzCrzFXy~>t z>b%a*PT$D?=K9SQ=#|MNSRD4#0akBi32GQ5@r zB!rH*b-3S4^|EuL03?LQ%92WBnujoF>C({QJsYkM75rL>I68Czw7OCoouNTAGYb zttXcP&;2~u8Ry%D0XNu-$ice9FjbP!OBjShH)SCfcM&(a6#HKJ79WBb9!kS032 zw>~!~spmJSd4gG#>!=8dcr7wZU|Y?YUV)e=#8fq)<+gizJVv*+AV-Q!~i2pacfY!H>V9oJm^08?B~<{`kaOfKpYrCU_)oGmJ-n}PH5^}Pay3$1T|55Fii`8RZXq((QqxlKSyxN0lQ-IpB|kSHVM^(cMsP$ zqRKx8#u*h?I|J6|F@{Ind)1nRy?z%s7k#kIT40VOj?NX}ckVEvK;;LF>4Skz1$ z;V=aLC0v3UOBZjwai}^?ulxBnARrn0D(K!sFltH`p{LHmrls^jDnUWs?lGq65vd~o z(jm{Qxn^=rq3K%RJ3m1Ne_w=_n^RC|YBXJcD~VpDSDEwN3TS1T{M(!NWBm>WY`{q+TQ zC$B~eLytWKJ&Hvj?sM3oWGMDW%ikqrRjw(B|d*fiF=pGhVL0cw518y5&%dVDd+;3;@k7GO11I? z$5UONV+XJE0G|7lQi5rPc7hozre5>;d-PnCLYS4MN(n`mt1T=xI^y0v`Iqp@x9${4R- z15N^ekkl_;6Hu&!;SWVPH1E=q!3Vg0qGaf zPTfRLbDU@A9{=`s$`(8*k==OtxP*C#b=~YF4Ac!6_XYRwiwyNJaAz5_bT8oLI9me* zOQS9`nvxv78LMkmFyiC3gr|BmivkvBM(<;Wh`BitI`1#2sPf8pQYhSNzF#f#S07(f zu=xYx|FD(+`@I+SbLV4r%!behBTFsuhj*G5y#owKx+E38a7;mqOTp-3{_n0#d%gY?$}$T% z%$Na1hNwO%0<5|DcMQW{F+1!cXRNrbL)e;)C4bz9|@sUV>j+;VMn553w} z>0&+n=W!p2B43m@dIa4opKgh_*3=_-JGvVYh#%{g6h1HCc!7S2&f?*6LF}*=TeSfq z_@2))0e~bRp!5`v;23y0&^ZANdALlU6^0Q(7mEFB8(k8yuJ=mMi8QmHW~t7(t+fEZ z_Y*Nr#~i-H0!666n>oLK$L3=%R^#ojC>onTj*!Fku7Js;!*P8 zs$_erouZ(&5J&WRT}(0`^E(q;u5r~Lu#7B?e4jVe^VFcrow2yS!RlQN2%^~kk%zI| z7d)_LIDWV=UIZzjY>n5-B>u#bu|T76Ubv2dgxo9!myk+E8VX433$$G?)CZu&Hcmcp zf4>>^ds0?GDoQjWJV)COcKaOYcrT+C{c22QL~GnKyLQV*J>{Q3w1X)8%iGNjT`g&i zW_Pf9u^XwuEQ@!G^;4WYQ2@w+{7cBRo~}*4RquxS>Pjpf??feus3QoWCN#eLq_6Q= zvqri=dcPjV0Knz~ts`@xQDm?p{nHxYYg=r)!6yH3#(X|&*loPf&zm8bUf7=$f^#!W zX6ML0ulpqsk}hs7ZkoYs8I-hsUi}CF41!tCtv5atSLH)$|CoF_Gw*H@_V2FPDdV?)EhWi`#nqr-^&YsP)) ziHTBnLeyQZQ#eg}KxvAJke(-@mHjMpE8WH(P6rlYN^w0#wX$Wu#+G@*+DI#^S1h&9 zI_wZs^}%ROqcN=|x9@FJU@($6A_i{NW{AL0NMZJeDuLkKUsm}{d^=U6<|Lx+Ii*HO z%2V-$Zi@xP(Z$oXogyNIkiCvwNR06Oe$+m(_ITxntcPwyIL&0C|D!$Hr~ZqwhM2op=@tyiM*ICj=k=Y28Pfc|P2DAFBz- z{6b;8gG}KzNY*^8>lUo1houK<;@xPxK>4Hc{Ml=GP+Qx*J$FbWGVEZ{<1go5(b_QO z(4HJ0ELMJScV2>93mr)QK5!3UVLSy4Y1~g1mE(i8Hz9t%gvhV94!?S^zdNJ*ZJAsH zkULtOdtrpbheZoafV}N}26_S|_+QU(2YR5=GjhlPLwzUOO~1bfe@&4rB;&52yi?ZG*Z`S6IO*VF~t!$QJ%}yYWs+Dvz&5)cSg((lG)6B$4qmz9n$B3au z>k&lIEzn#*|MBq9JyZUE%VWG6cJrAek$*(Grbkn!IAz^$$=rL6Jd75ggRgsI&9dYA zf@~`n-z-l_#>V?9VR3vCc1H*iUs#f2QV18YtTG(c1BB;RmtZSkeECz(G@h?5ya@f| zC@Gw273b}^I^0t_d)DdF1|-3tluaji)rOvQ5bK~gfpIHw)T{;n{dU8)~J zeCst&I)fw-NeTGeQ$1cgR7ab(`e}{LRN$B1rO2B{^TOih#$p4%p{;Da^ixhhjJE z7v0iDO+dHq!!gw(TjA}cLsIMh<3(N1w@ORY*udE6xes8y7;(wlb~LND9~Syo@T&#a zvzCzET<6InOUqj&U9zpxWta^=EWyGzhD`nL7~S3CC_PM}nmhQ+Q|DO`5lEh~xkit0 z=;s<*q0Rbi+El-i+<@C@3 z`R7+n%5ZNoJmqMj*0;G%Se#fN;M6Ek-1O2vVJCUwU}HGRFXylRb4JM~k}5^kct-Pg zg+%25PyOgonMP>ni)qsNfoeChA*nTI59E<|DW$#BA6n+yhKN00t1=i(NW6Q4bZJ$gj0{T6cWp~3T zCERkA?Xr24fy|Q%4P&QDoSy@TP!YohR+dmfGuCj~EA?XDZK2{jCVz>ET}{+0fXI)W z7(Ws0kG}^vhT^Vf^o>jruXLMA3}HOx0gcIFIAOtd;>n0;2Z2mPZMPB4I_v#<^4`|- zWCymAK^;AUx$Ynk$SC=3lR*Z`Mapg?$L{>3eqBdS&B;=L zwY9u@*oMW|C9)Dg-s(Lx`Xs$t`*9X4XUvmdJY&B-Wa24wE%JozT>_iL?oRR(d@G49 zgr#3eEqvpJ_7x(aEwjAefkc+V9>c4+EgiG|d(ip`(WfiH_{}CWu6fqA`~1PF!{jDb zgnZTG<=7hpxu$BEwqa5QuJ3M$#=gKp8Ed%4sYqZqoTgW$ou&0G21d!_enB61vvCp{ z_U&2v#RVEs6CBBB*-X8KVg*{rhpr=wjg340?lk;U6U0O1*Msx(z_;&yVm=vd`rex+ ze|kVc(D?FqA3+D}aZB=HhphYFkaexQd--SRlTtckmC!>w3aU9Z4gsPXD8P6d1lv+Q*w_WEI$CodD8XdYN79}^D;$kF9vq2 zA&HvT-Amql5ZmUU^;n#pKH$-HzADTfSd{ISZ;c@t!|6f4nEApdHHn zDz1tv#OC=O8_@dnCJY z8_gO9HAd{gSI2$W$q}w#?^Gk=K}9nJ^Rhk979J=CDR(lc-EqrMdd{uH?E6TDs0 zBp;f%wl7CzUn#{X60=G{4iR>D`8SrOJHa(x+*K?7ROC zBghzctGA!bhJMtZ?t8?c1I<2CBnA%FE<3sntpx35(&_DPq9`yy!UIUc|yPH&@?Cbqq|eD+$V z*i?=wJ*L~|fU4rfpM7se%Lw=j_tHuI?St>16KlVm3?9^^iFX}Z>r?kU?!uyi#Hi8+ zUUuTg;@Jf`6JUU9E~_#s4z|b&Ipg*!mF^ql8nYl-Z>78%rMtaVdR{b71`P^YIcCp| zB>uP18MWrfVc2=TWIK2`Cj=^bCfzI}5U_C;3c2C2UIWr6wI}Y6?PDc<>~mYB8dt!b zsCDX{J+9%@4DbF+!z50s0T?ddc^AS}3gpACyx`c7um6j)Tibf>97Btq`kyR-ahtcO zYhkA2rX@>9UEPzFHk(SGHRGP_wal9V{jOxxMe5=|83T8Un5TP1p3JBeRL&Z_U9WEn z$c)n`F{FRw!xV{62?ZAbjF=f2zap0xH$yx08BQ)fbog)SU4}@C151AfV5>5+Ek{q1 z)4Jh|U|ZAS)yKzI3JMZi=r6g`rGV@B;7#Nrr z4(B!o8(H{Uk2k{2njZ1TU>&sSCq@{$T7cZ%cj$v3^_oq5L2(~@8&V#;`tw-!{NiKH zNxNlm*UvepG(QrAv4U~O89FXxpVw0Q@Z9XUddaeOZU4T|vgT2tXWe^ToW`AMNIb30 z9YczHI-czG7+SN(ef%oqCPUElg_hinEyZw0UH%%`TGCl6RVD1|?sVGU`|hA825Whv z&T$vCkCp@+DmKITb4}fd$%RgdUJL~*Sq)-dzw!J_uke~*D_tq9` zOk3%N{@r#9ciLdo?}>vCLP4;5v;xY=py)>zom(!uVvWLfd7EcBp24^gkIhXe@KA4c zz&jLDX_OgjZu4Ux3*KAXZ$2@A55Q4#M#hsiIty5pmgx@)Hh&lyJ%7UEFl)R)UKnZA zMxIH`Mm7HCtNx&W8-F2e3Eg86eZ*(;l&zxX4i~`jY5tsJ5yw^!bIy_+s5=f#+`l3i z>TLHc@Sn*c&cxubX^IM2e;D+lxf-@wmJo?~3s`@q_XD9dJ`x;u!U(W*B~}GBMZF6l z3_k$GlQS)IJf5Zpf0YiTzOkwFGaQO*fl4u7qsyD;{2v1co2ndSUQhm%-n zIFzlG6H}u!qehV5F9!{oz@9ikmPdWzz<<2}`%GV5W$tdP&rfyRXPpa8qR11QW(?q# zwz+I1({u{@t3Z#BcLmZ0_KIdq+WTn7z?r_($PW?GvK5j3!sr&O)W@HH<+v8jED$iX z^e<2vdOXvT|EiPjr)A41Y3Bs1^xqXG4nFeIPZ1$MmUO5NS8d@5fMGm6T^W-*87c{= zcO}apbLGBs$`zpThxyLGgk}nr*lZtguhup_%k#ivIuoK?kC!)Vd&OK=W${vpK_A}o zxg5PdDt02Qt}QAwykd|MDq`SGL1NzNs0 zV*ii7TX<2HTMRk<4Z1J#zTV})f2Aq713tH)NL6OD9@;G8F|(exv~+d`g5alP7;D}o zS@bY_eCU!`vbHg1ejag7SAP1oX7^dzbX9UqdMj!Tm1!QfifY*iYYl&Pb+=exxpon} zOUE_jQFc8EH{(ezAMNCE3Nx-1+`JnSA3GGSY-)oApWFlH(M-CJDuX^^nKPkPf&r8T zmK&c2NL&42i7Rl{d!kG>Kw<{h~f>%_|Tf7fknVjN~Nv8I(Gg zEuWDw6R_^p@g*@?=}DYf_NOOAO~836{X$(nDN{$DVDn?`ChH-!K34#U2k?4MdtZ{X z4*M6*N6r0&P!7idOB|cVRD&HAeb(_Zg9&J4OuYe3c}`dckL}(?Nn$n6w>tSdx;?sm z(q}Y%6*xojghJ&O&jB2NZ386}19c^n4IiYoexJ{5GD^AvX^dZJ+OQjm4OKCK{?%F4 zeC+kY(h*ROMqXZ~@%U$JWqV!xy{d2#8*!=aqCQfA4YFNwOt?Gx#%1ekOI?Rg2xr4q z@}EzpJU@n)zH8#slk_m^p?oFS|1Ox^rT92CxJ}*~uqD~M^PCMTr{tuAEe?0a8&1@z zm*Yc{jr!GgP)qttPs=%<7x!RlnCKzp{o?XdK4iW8zMAN4fb&VOs+P>%T?67Hl41+QQ^4xY*vWk}}dYlP|jQ>>DQ! zls(?%x~0!avPGg)fK5~58c)%^I{Cx%2Sn)M{K60O99SM#q#a+;nX0>1mmJP5e-v?| z#w(5;Nb(XJ<+w=?DI<4%Zf}`(t5Th}n92_Bj}N7wqHc4m-EVi5N6Z!OOK4;+KKk5G z(#~no31T+>&pqe=oOhUBV)1W;R%SgbcQ@8Ee8A%vTMxi&m`WLkVC`ovkcSdkBL{Br z5v<5N&;dT0ZT?TPKlqaTH}cML312HP^v(PD$JPE`Hb}AFV{_kwWCj-C4_hYJmWK>J zfjVG4Kh4ZgQ^4|5exm~jP5f6Gs?__V%?0Q`27O!d-Jeouxle;ft@v*wGaq|Hgl4bY z!#mXBZm!rU+j)=$cZkN-YSRAe&9UqESzx$0kqtu?C%l zvtv}LIqt9>m)Lq@pKZZS-N|quJB&P+OXg^IWR=_)pu*r1qgAMYrf>8YREu09I{53a`aA7}R-$Mv~{;V0bJk-L;v4N(} zl&TNo-FE%P;26+^S3eCD;)T_kKm!)Zj~Y+X50_5vy+_ zTNXt-c5z z2%**=9Q52QHu+7xssUV>If0NA0h*I!W~U&-=SG!PeqKKX`R6UUB1 zcQCERD!`<+;a&tFXf4+!ZBAiMN2Z%$;g9R}5z?Y@G5xFp1LaSY~jP6eb%mkQ@+f;Y$&g!mTFW^_QF3MGfK_BW^fYS2IH+_G|P4EfqO^a$=60qu( zfK0{rKF^?GF<25wcRgN!t=E9lx8<4R^}kJULj=Og8X&(IFSq&>^{*)5&nYK@rE3Er znF8kVFuZx5Oehz2@RGV%LP%TSN=sOw%)|8$?R5PL3g;xRSRX?~B zzskX#*o`5Gs{|z9ZJ0_MI)2j_ghucgigh3Qw}-c%o(Z_~A~t z8U*Sz0$Y~VGW-FuP;+ny%tD`V3j1>QPv9@S=>)fVC<*%8*KA3U?lO4=co)#EH%#lP zuDl%9kFw?a?y1oylfjQg77O)=3Y?hCdnXGbvxz{`|C(cIk3ddq=J>@Fk`Z)diJS=0 z^qDQKl%hteVfP;ZcDana4`2F%vc{IvRt3bnu%_Dqs+!v1>*Qm2c~m$N&H}PcQ$O&< zx1Lt4=ti<<3L9*l1?B4B-7j~p0iIK7C9=#ZyaGMi-S_uvb|J3un(Ilw5nchtp9xE( zr91K|yNo#}ZmUem{)Pe~a_#%Q%0}B9E=QUSEx%k*rSnST4V}tLxi7fZy>8rK%3W@7`Gz%gIRwDxtMjHKFzq zTRu~vgmPLl>pcRN%?)UH^U8~B?XO5BWY(E90zb09eb-xQ&YB5@>-WjiQ^8;1rXzTY zjN4mHlasYG$E_;gdQ;XHeWIM+=RURKK%pd^;KXxP`Z2jw!V^cbHhXyKuKANVR{_D`*U==L+vlA(X7-IC!dHQ7giI4C2Q_UhkO^kCl( z2-Uk9j>29fHbMOvRMI+ z;)lJ|M4*6h%fbC)U@g4Q&)F1TLtm6QPX7(qpx?4zS80QuIxnhbVst#DA4fCChSoE7 zOcBdQAj}iQT4h6i*nk)DOzF8k;Lx1ThYb64M=N5b=2-3@5;+%45@DnnFlJs0^;LE9 zcv8I|b(l_(J!kgE8b6#cvYf3%HN9xGl8o?_pzxYZgzFXj2TvdwqBzvQTu&Qg9Pne; z^%tS0xw{1#XT@~wkor$)YCh%bZxc%4vPkcLL#un_n~%cF!T|uRDK>JUv|fPwMI1l7 zCk@5*;#$jSWHM5@8!kMSe2?=5p3vJeaW^@kul|0#)hdXEXvJ3;I4DTnh4U{R zmai3^OrMua`V+Q|OSr#fN^Xv3P}mT736j^1`*&xiZ{dHVwzmeuIB9EPSB)zdH}6zC zV{dG9{Wgwg)hPhY0ZII|`ddko*%9VtZWe!}ebRlaTB(sw+KSZzZ&owq2#vB;B#Y_? zrPLs23ddwvK7p(h;EN)~3o~hAKhliUpVAmxrVde;DTQ3FPC8>O{YOnBenSGK!oE;3 z{E(uUaZWl*fu3{TOhr;;k?6P#v33U?NckvUfmuUNixZ(yNUeCdQ50u zS>#HL4h)&w0PW= z=r}kd2UcVM^SxL9+XMb!iB8r}eR-^eD(o+RVo8u799HF3iXRfEu^10wMglKBYXY|Z z{NyvO*Rfc`*yFzcxO}P!Xnp~(N2Af>vvP1|((*x98c(kDm_&YRe=F{{gb*j726PTz zR4ANWP*WH38JC-%(E9>V)B-!B%GY#!dp#D?^3iBgO8s4QRfF}5t!>}UXA1zLa=d+E zy*0|O@X{C5B*^85H_Be`xz+cD*m=fI(i_RBUx~XJ=|Gk$4L!6asPR4(=!^2OrJCqs zzsJ}9z+MYS`a!cQY-_cB$F%SRLs@LywUBNf?Xg@kvi<+ytm(-FCpbp8_jzlE9zm+Y zB$p4)vvl-75FF1>Y05HSP5yx*e2C19uvJbZeF_hR-$b`(R@n5PGj8qB zb)#DE?zZ_MiB6f8lAuX1?#{L_9MnWOQG*3HNTlL{bDs0)$7-h6PUo%!*sO?@LOj7{ zDz9G#@2(oM%c{hz_T62B2AEv;&2yZDO~hL1eNrG{ej6!I@;D&RW|ztc9np#2sQs4f z{s08*1L^RFw-JJ?0#two7BOLVL84sKiL=v`N{9x>LJXT`E=)SC;I}ZDB+`0)oRN zSg~Ku#=^`T_5G82`beeW)#xlusTz)-6m~A^ZoXCKZaPe9Lyj~1ijydRAkL1)&J;o; zazWi8b#zpX5Neg1?pu1fn%O|sQhqKTkLu{7;D_9?|3f-us<4Eq>(3~rN^E0PqF3YG zPEsra?-8)7Ly&&A?q{aGC4+sL2YWfsp@_gRNzdXhVs&(jQ_{^I(L~pfn53&2Fsr%H zMu0;ue3cDY-(reBXmDDVN>*DhWL%LPzh zyZomIg5~U{N{?>RWD9QvA44iSJUEZFLdaOe>({zXWf=1d7w}#Fv!7(I6MzWv|6Hiv zTWkdR`eZmNmTR500*ii&3{b@%!PE=s*_HqZ&iBla92KqsA<~p7hnnv_(87U;TQtDh zVBy#DOY<{v>f*QD3WUVvfM1-ijmL3Z?K+AXf5m51Y!jqqnAQCFfj#X)QdCPq3`>h( zgFl3vZsXf6CAq22v}$5$W9fUmnka=w9i)J{a?x*F=y4Ya{K6xmkVYo3V6iQ+!`k2ZA?3aOx&7#7(soWE=kFTPWXTB7+CG zYaR1X&WWFud_I5RR$j86pdPrEep7wCF!Pu1O5d8haN2XYL?I)Sy~b+vGJGXDDbopp z$I`(1RXeJ!*(3%#;(lxze>3-xsX<6ioNN)CX};}Z0;o3Sps@b=jQwU^oF$Wg4f7En z5U#I(^w~~C)bDI^>(fW(T%z-vdJ?@yVULQPCcwl;Ql@u&m)BN7G#GVU|6G%Xm8+|!e0=GinRIvb3BO=3vgDsHQ|0=y4HBZcH11y^gxA0h0$jC$sM@iixvAel zbmVzp*iceo~( z2n*=rqt9YUeVK^1eBbP>(ChU=!+&AX16ms@bvK*g?{Kql3UCDUERqzv=y7}5r%NbP zK(R2w$ZR@^1T8FGEYK<=)uw+yz<5o*bjgnfDuBDmHgn&8L05;}cm@|WrI&P+A&%m< z=lni8x(OON^#`u+(e31t&_lRH0CJi#i(y6q_=-OCwsuC2;HX0RV-Bao4KssZE2Rtf zW?6Dw0Bg;dUj(D**P^Pq=&S`MwzgxVv;RD2;H~O{!Y%ehJ4>jz?@cX9NSZDNm%gdl;$YP z(2|Y+VkBFg#uETpIA^#(p1`;)J5e828a(KS<$uf_)+*Tj%jW5G$MSla!5bvgmgGrK zy9HfBf!h-naz>UC+PB8=x8zJSoVX)&Kg<)dkTV6qm+}?cOxC^!9TA)oz%R6)`eYy1 zG@9L?U+lr$Zwu5lscF?9*jw3Sww#%x|NLceEGB}U60InN7!Log($aewerLg zmK%4Izs*q3EEe-f=&PaMA2`zl?D=^1F%|LBoQ48^g{swiWAe%8G4wFlX%=OD``zpl z{b0H}c~QRFtrY(7NW4qIMp?-DYlW*Ezo&pKtNbtbS^a?cv$H1(Gv-0>Q?fNb+Y~7f zp3Q_b8IiM}_J`11Bsnq6zhH1Hs;pE&ga!vE!(%o(9G1~CNgpOQ#Y#-eH4^@;N`x@NtFiXmw&F@tuyoZ< zfOCgeTYG*2h(53t?Kgvz0k4}*u z=~13m4dC1KdE78Mfu6t7r^+BExcdOMso$YcELtQ11+YmsQ zU7MEiN5G+Wx7Z@F{MJUe!yaQ20b_gQ72lfw;=X}XbjzvTK}k)S)EqHC=bgir62C7N zVn}QqDm*UpXIYcB@PjKakRB$*(e$q(ZzD5xse6x;%>l68xHI^)UTXpeLJ-$!hY`4$ ztNVM}E*tD!%b@mha51JI&Lu_2uM~lfjtW6R z8RLI{w^A38B|Tr&AMJEUc{jFo?g2`OqdyR;=#ov?XvZYm%f$GTBar67=+b273@)Qqp)DKB{;)d;Nx(b)@1YAsSc1AU;Wm&w- z{V}#=Dlfmb--ucXoU7qL-mcsN5%^WCP;l@66kE2J*nYU48^mM5N-GE7*FqAKS?Amf zCzHdfEQ~^-x6@TFb+;f?-(h4v-G7Z+PPf3`=MnR?3WZ|5e<)moI6iZ4j(p6)y_=lD zlS-25g@zx0Q1wtL>;#Y24$QU|QDjNF5juPa)aw;eaxVe^gsnOwG-`2!cLg{adJ4h; zFN=AQo~2eTxs&z_zx;@VvQ$6xD=5JxwcH~jS}fDUqkik%N#fS%s(aV!v8%KF!Y(Qc z@f8~}>oH;9Mf2#5;!Nq;=rmO>HbfN~+2fs7;dxeOOc=3;*C<(6#1)^am()WeEy|0s z{M#DG_7nUk$7IjC%y>o=xf22g-dK$9*Z{p0EPRTnM#}w)|s8Z%lAlH{z-k6=%Jr|ux!=EM)<||(fdm_=m z{e;`S`i3d&JHMMq!f^d>8l0~oN6N__skPt$5pP)Yd*N@sVsmAz6PD^*%OqO6ancCV zu-!94Y$F2&HNrpR`ze~WEnU4al8Lw4Jn2?wrX?G>Z-p65=eWAeCY7|sZ#I*WzZQbB z4Tirt>O9M;{bDxwPu;9tN_y{H?N92|!}yZNjMgL273d^Rp*i55kfcY3b*M$?ln^Co93$y|xFp-?POYYaaAc;81U~#^_`3rn(q^`5V=DLkY`xRdbOt3%rKa;nw1n z8KbyHdJQ!i>@6snGA{n|woOWJ&S7mW-m+l588}z$lSh)nV3tVAcuEbw{`05Ul=i%{ z(RUl>%*Ygt!ICgfoVuf^_D>{jF&`a5!hK<&i+nuaSe{@(?_f+g&6L0V*lja-BPeiR zzc!Vr=w4{PM>@bw#q_&IyAOSqvZW5*sh#D3m<;~gjur^GdE5rkfOy+s(TI5a|Dk^G zZTP`=R&88pt?Pq*;{(H&-X@s2UE}p9-iEEYLlyIT5bA#`TnSS-LAkX5$pXAZu!@rT zgP|A7MP!W^Kk`}0rR6EpK5h`{+dqXEa1&+W<9a?PB*?=no9x4q!UwG5KK)x0Wg9em zo-=Ry(~kDWEH>6^pLl_tuYm9}CMJd&M0rdL1QRkiJ<5o^V&~1|$A*+tSB-yG^HfLd z&&+)M0L1bRVo?xESnrtNl95r;-&dCEqBYu-8mw*bc|n~xoUfC9Rom!q5bRinLl{OF zDapERkE@UZSv*LxYjdR2SXN^@a?LG{$4%P_xm?>n|H$py5p)Z(%byD-7vqR9bWbRx z+8yvN3agE<$VgmU3h4u$&NKCeOXKhEWR%o@%UBR_fJS)ue8LPJ+Nogxnq6Tnt>~_!4UVHNZUhTV5Tw zWc_~H;O0*krYI*rt$$uZ56Q46T#)MQr4;T*0%d%QwsBP1ExX)l68To4)%3Bpi zbQ73Ye*HF&VBC=Ji9-e%!0SD7(TrPT2MK(?>e@7;mx?8Q>3F8pFw zo0{v}a3D|N(!J+B7EO;pn5RH$%IxJ&5~a^43;SHVcg2AXbsGYEL}+YTiT6d?++_+I z`vdOtFFLwg5WyYYEtsbrJq;Msj-Dn=aB%l_TH8?U7xMfs2p<Kmz2~{qLR`bBHf+B0Fpx~-Giib zNDTR|?{m(1-}gDc?6v=Zy*_KN`@XKdm;0FQjkW7HN$GHcUgq)2QRgZP1It;W9>f2M zd>Z2lvds@}9sVUf$gJK(rijUC_n89SegM&KkN2JOM94}IRzPBGw>puhLpkB^lv4(k z*UABKin86p*Kz0=2g|Kl4&4I<{^>{1X6P{o5Fg)6qsAuZg~cR?tgN;u5pvi*+uS_k zto~zHY0zd}c!Oz^bMgR-zY&nWG6(-TroBuXINU=J`SBBA=$UJ!;ZJ^U&BwBD_$~NT z$9rAq0m;KAq0g!Z3zgEmC(O7m!*U%CqP_ay8k!pBWeA=|;U=1pI}hWd@|H1YQ*>0=ra_e@?@=Pk z2~x_SeE7-TqL>-y%nel^ryg%lMQxbTGc2(&K#;?sb!0S_hP9pZ=#fLzXdpqSxQdSW zd$qCDFqk_~H>WjR1DvM&ktSd8jopj}Cb(-P4^` z>huq9##I}5S4`$tPx@c0sll_;-}TEf5>htDc)#B`OOaFUeRwZ4x8_{ksW4Mz^mw)F zOb;{kyw@bIA82WfSW`~=ZiYlg?2`lFxc$=gYJQ{TW2xgoYt)Sn-n*7|X92@)$)^c4 zxxhT0)8hhZvf>&>#{Ge!yt)BI)L4}*!Qys}GvvJ_cZj-QD4Qk^+=N02Jb5y>w-9n!4oCwW!^N20Y$AG=rB$E3)KMJ6V62S+tt_ zmimMQZ-2Ks?lD|;YN+@54JAJd=6pZ(^$r(q36SUDnW&(Xr{C8 z9=1Y&U2fz>g2jeS;VXK_C%kXcTdP8_ZYW=fbV1g)Yq)0*oJs;?4fzMU?3WjDG%O)f z(}(F8pRkTrvsl(NFX1GoZYv%{T&hAQs%)vliP2$IIyu#a98{!(caDdiU&!pJ~HBH|4M@-fq-=@zpGE* zb;Bt@(qA)+zKgsrZw;bjD>FI4y^L@`KVy9YTan>ZM!xJp_s*3c+Lb?nVUrBf5nE@& z)Yha^ZN{vWu6}+}GZ)9DOv-P`j>Pu#8Hd2snt7)-LTPe2+b=Ir)|pM%i+ClT@V$}i z)X-f~U_@=OXwCT=DfPLylXMy65Zib;HL09m>N)3U!qel!GN;8RWlsSetPd)Huf?Yn z=wpeTFG-MZ+i!{sUDevnaH4h}TGs9AK484L2+5V@*6*R7th1Y<>$`}av1inyQ^~duWQ}q?Z;UTFrnrwb7xfkoi^jM``0^HRiwE}z+1|& zuzjxoZM*!7j&OTS#(MJ=WaOOp{1-L0+vn$2nbE9q+>}T<0Ng~;M*(|Di^EMx>an@U z`;&k_PDci!uj$km7(J?EV`Iv&-%;rb!~|5pxVh~Aj06;i8#IKEVclK;adfni1~lH^ z$(#}ep=@^WWX;XTvl{37>zT}{Op9VX6&ptc`uP1&uSG;^04wSbxD=dV=8dz7evS_^ zzE_ccyJdXdqYE;x3YlmMmnjH{SDO$ITPk(uM%Z&@?d=%QZoT+SvO@CM@Q;L(x2TQ_ zK*yNBdgh&XTR>P9ZpoNw>b2h>BUJ;iWgxYm!%JO>oQIrzSPHEnC~FudDuP~;K_2jW z?2iGj#(ukMpFK)b@HJSy%7&*QQ_ucnB58BG-{Zw^pB#1z-PJQ#L>O_rTb2EI@dwWJ zMdyNW)mO9WfEft>z~Qdofge%|+Uop}cjX-NHGM+->oDxcqZ7^wC-y;Gk~gE+9Y*1( z#q|AwLYK>3iNaf*-bvjWMO69j)efNh;-rKU*A>c1=W$%EY-d&H#@C!-0+(1 zr1Semc-ngu%&<6LAX$JPVtlWrfR2#dLaKbvEL9*|;@F$5m{25YzxeC8oSE&q0W30U z2FDKzd*?A#n6xt9e3a>cUMo$Tho1{2w}hjk1+1SNjm#P53vYR6wPnP2KnQhhL|8-@ z74e035rOYD7wMoF!m5=)sKVOs$5MO&CHGOJS3U#^wh|6lKVo^pHllT1?&GIJO857zKb6oDwDwF zx&2NQzJ4G~xU=w~l!msfCD8nlz01e?$s45QUVCM9HxU^dNwm~(VSN{Qp6h*Ia~Adw zC3*~!k*{080_X#m2+mn6^Llkb6d=_}UA!Iw6Bu%yl}4~4k3ttH@KhiXwy9rOTx_T) zaFA_JsP&OnImmM1%KP%2qYHfNE(Rb0%MZ12nel5;~N7G}mk zE?)1vcck#S#a;cBu5T_&wQ9CtFqB;qgJ9}RZ&`_RXm1A<>&GV_-=t^3o=qhKY)9lP zP_Jdfdq{ruyrR3wi>DQg7n=#s7zcVJGyWZr4<^E5V&7zmFmlPUsgr_m0>jVA)sC{-f(*(YrQX8%&P!7ll4^Sp*+12Zm!|XB4!oO_kKd2>Qu#) zvg0mG{Ryhgms)DVPhEUs+$WVDl_BZ0T^JeycIWQrnTvcfbyoHo*XROb4h!4^05>#L zmUorRj})pbw|>Um)b4rz{j;@dgmk`?bF-uXY^Xwqs?6>CH~Kw7tb0zqX8an$ zK4Czs{$&$@)3ZxyEsZ2#XYU~8?uPUw$&HA_yGJ)**fY=%+CqK&sZA@jqD9;H9xn~5 zrIoANx2EfgaK)x?e1=s!-6Bm|FW-H$Wk|XTzx965r2#FTVf%OL1|QnYj#rU3-gjR| zzFFt<@1!&{ojbGNW2p#kI17^vzEpB=584t5J(L5$NrmpR>jLH9&9wx&Ug+0fTb+0B zKELb!dY&7Dn|7#H5@@+0Z+}vA|La;~PvGEsK{>Bgo@hathYIOS0g8O=%aukbp$nt{ zH4i-b$!w(P!!b?W=4#XE^fC({jjN08XjcZopDJmC;t@3p0Acj%Bar<7$!y(}+=k0d zF1ABPgg|A8v~>Gaoq=-%kkbD9Qu{X=v9`O@L3Yw%Bof&8mhh-ql~1?I z3~{JhVO15%b$j%d=eAe4k_=2+>c6hR{_FC$+#jQ#`4jJ%k9E795_^2=1WDS>H+nga zIhL>ko*>Ox@!nt@04*PW5H=^{+`d8vE|;~Y7v-YeX2-VRYV&g7oY8?-%wt~#>Kt;?)lo~@=5>m_i_ze zLYhc*zkF=!9d5!g`5l?7Dqw8`X6iF}Y{(FLV=(4*V1zw_L zFIViwO%E`;`0|#{e|F7l^Jbvky?8h8NNssZsBz12XGs269*MjTNt_^kr^SGC z+iOSbV7>(+8F-7$^veth#Tozvu1ju!4#9Z+(m1f=-N0hh=?Fdc8)&NvTn(k8WN9LQ zw9v>%j0n zpCybwx2x6nXy*y3RPWKTR}!I^qTQMlcr0t;-sQ#kSU=sa4pJ@DdUS|zP%~{iP2xU3 z8ax7a9#PE74AFX$jzI_{4u6S?G zY|>bQ6Yrd@7`qvf)-VbLVa?4zYA%Tp0-(s-W_E&8JP#Ux6V)O4U-EsW?(#|45UQgp zyv;@GAh)&ShRJ&&&rgbFi%ptC&}EG)xwM9JhVjGI5nr_lm!aAF+J0rbCp3L>Pucp% zWKORrP77UoLB7Dx=7)}t`0fX9n@Qfa(S*2wjuQlw&`+7AWtF_Xyt_005_*FmDt52H zH`G96LxYR;h3IxxV;Eca00M-8_I)qncg%~MJvVPDY5Q469;X3j*I=y$Ls0fSfkJ2)CTvit;(K2 zoX|E8P?N@rCZ?boEgl_0(NG<$zp0ImIqw$)eEpz^Uoq}nA|Ad4C86+`eTM}8jtPB{ zpEJg0D3D6Wlvx(_1wYD8kd*HiesH>YI`txWxa(3{eDLW0f>>Z`+ofsszb_IYmM_8g zTh_rmESQ~v7(=>hX)B9XBVfSC?34Tpx(oB8J<|H++7=_T3Jat5|1TT=pO8GZfCcUq zg53a-0Sdr~86!Xv1bA6srwDS1gikL)Nbw>JA}k9zh|7rkSNa@@8Ki16!yzF7j1}gI zfp0;yn(VVrVa?%h{7Q)MgKoaaixVSemnYeA^LETT-?gIlG)&)a2rc8o8AFv4j${48 z>j$l+goHkgR}c}A42H=+=m37JMI?y=;EjSsmCq1NRsvN0;XlKFfEzTkrNS_HcE%(N zKz+X9fNBSp$|fXW1mHvvS<9bmCrYOC+5#X~!re-|MRW0a?f$MEXzG}u+Qhd43Ecjx zKAX-&KH6{do=w1$Puo_rL}uScpY-H ziXTMa`+onGI{7`+aJn1%_qRS@j1bFZNLRT!Wp2hIP4pLcGxX8z#wFn0O`YESZIz== zs-@qFAHkulOrg^B=2Uj_4NHKM%k`Q;da^_;71cMu-bYgc$&l?DBG0G#^TWR7r*tUc zV!q^3pu_Z^C2AlyRUt1vRgc3qlZ--M%(H{Mbh|XxMw5&mzTuCO+O0p@m4miHo<}_- z3#51^zb4u2I(MMPZ4IWKe>YuukT7gFKrq!Y#K~KH_G2^;yGCBqQe_0 zX`fdWG8tm68wUE0dw$J2_2;{ZEA&r{t#Rk4Px!E(WgzjZ{Sn*7v7cYlCnZ?+7-6Rl zUQ8R({M{tW1Dx7(D8_L`UMMX3q1M?Q0k$^izg3%)X*ZkY7JsewcFZuSEnEycLg4iw zYx7GIXZwHvJS-up>9)3ZLh8L5y*O6fWB=7ULph%_526mE$2u;4uYl**n+J71M=n#r z4cILJGoN$i(+}nRI9b|*EP)$u=(5ZZ1dNiArrSSNeC7jNWFu>~1ur_r{?q0B-%Fg`w>I{|)u{P#@cM{u6AVs3F^W+pbNgy>tohs^Y`DB^t``A4#L}P1$!;E8& z1HhhkW`N=-5x0ETPbcgK2cRoU&a|GNw>!-XKh@OfE%T<=eW${guU|^3;7YaW03%#n z`(ov{|1)xG*w{Hc{YD%RP^R$VcO5~d1q`TvUfvqQ)N-zFt|U^1kjynv7LQ@!qBQUw zyp=JMpVgYKfPBQtLyb-^43kTfD%2-RCafdgToL`m$vop5d|^xEjif5oVn1@r2VwK< z#{=o?)I|uwO}7`HFoZGv1#LyXO2vGFoe*+7MTv>YeNF?yaS1FNo%;jAJ2UEOCZEC! zWkuzwP95G`zOvYu;dt^Q1a=a21ny(L-sRf!%1emB`rCDMeYVj+T>K|Mn{E%mm%BRx z3|~3zjocW^JxED$gCLNDrcnXS4YV^fVk&)*5XtE}A;w@FrxbV&+U!h}-A54C89qOU z0~BuFMs)E|9OTjY_vkMujgJXY*SK&lfxC+)BtKxzFnZa!D1POfMHIiRrHabHMx=aa z@t?P+Y3+>T_kGsQ4b`S%S#{*@D)WK}R&vzPx(>kM^&OO7Rrk^p&`NgOgqRxzOc=t} z81(u)!HYH$_Kp@kXi%BIpXS?nvm#p&1pjnfcni2&CMSGlNnB~4&Ll}+E!vOqbH5xJ zi6<+-kdZq{l2lQ8d;7E@RXZ=}rtQxqk0ltOLihQtVRZT8GWAfAweT|;(8MCPZWqE? zq~EIbx)68c#%D`cwWr3A#SM$0tbo?0`*u`BLPc~#TYH$Hy7R?*!yFDOHPjQHopfC&yU4?;HLR0*@i$|EPgs)?IP{sVSKv8(Rl!B9bK>1dURTE(rZ- zMQ;mhOo5olf5j;Fkpvq)(sB!%6C9iLwN5Blj@R#tD-}E$APizv`6ywYHgiK)7E(G= z*i&Cn@En*>#tmG!3UqQJ0z?y-ZMZ~y{nFK!KaxGHQ)eFL(vdLN}fR9IYXs9Ut2me&&StE+TGvS@#KbEQ=rTmm>EP2iW zfcJ;n=5w6(XwrGH3Cx=bG?^z;@}jB(mo+xGN#!8&!Dx3MRV_rEZF~DdA!&RIlV6x= z9ykBgI4cfK$qmRda3Lcc3GuyaiDx^q;pb(u-EZ`2AnaPqcIwDPObRx#D z{3=`0w-j7t()?McQeci{=6Nw%dCYM^zTAP)8R1v0C&rJWsmz%ddn>TK5nDM48>*t7 z3aG&`iay`@LWIM;8KpehI?__MyHK7BQ;zPYLF|-5aZL*T0kPz0r!F*hDf8dQ( zrJGqM8&Yw+YKN2?@_)e!V@E8O6qA41TRrjDy|lBLw2m9TV3HQSAEHdUz4M>oKdU0T zxb4YVojWVfOY|DU_r7!ApJkZ|p1W&b?ppl!;`yictk_(>L$HcP6X?YLQOn*|orgiq z^*_Y$>E-^`a4;E>WVr?Ze26P99cYssDjZo3|=+a!^Us$pyfX4*L zU>pnC_ro-o1ppU(&$PHlFeNn{zU#%NGvB}dY=H^`;tl&`QBxj2o~yw? zaSX#735H((&V{I+yxJ7l=BhBrJGh9{O?z}!s#4_hhW&KA>&66d{7qjGH?Ve`OjcBg zJGXsPZ@$)*C=670Zsdy|lsHKvza}>!S0N|4Syv#mhJ+R8ae7I*J>7TF;}BHG#`x!eD9-OV-jqEq`{iDoCuIKwFY;Ra~Ovd>Lozq zTmUuG-r_udXC8ZkCK?TU)Y5^4^c;*d!w*t5EnI$vLnE=z@`L0+eeqdQ%?R(d zBm>V!JC&gOK_JZ6r+C{oAOo@{Cb`#O(YoDz@at##b7nip2u(bTB$kGE*;jUgoz%D?P6mA1^sJ(OeyI+}F0|8*RVUp36P_F}r1w+Ji!T%sS)rgb?}-syB3eysH}a#moDlQpC>!&= zsJtd8!!%`SyE5L=9~^Iqu{;hIn+@CA;78E`-QccpeZ3Mv{B67jsRd~&)>I%C{u}%C zeUCONNBf>NnW;#hRnJID;Hd-HG2>yjo4fc5`x%zO6WYSMgzva01sJ!F9#v6Vam*vy z;a3n*sw=DI@b6Gf;buP6PaF+2J(790*9_^xgm6TJdob_&=&0>U-SNz1=r6nr`wt5c zAMqH@hcF>78~*ggeYDFY3sOea06}~q^lkdw(WCp2({{o8l$}e+6Ii}W3xV}V5V<-y zkk53ELDJM0s9{&X*T|f6=qSnpTCE^~__52m=k3Mol>+4{KQ_aT+Ns^9`gB|;M4JTw zPj>szXdq^wT8{O(wely91+OlAXz7&gvQ-e=u6^HvYG0KMInh;D`VC~dKuwWBUUKS7 zW+p8$4^noZOzG|8MD9;jmD*_HsP<2RGA@Q>s3S_PrmFc%f3>w1f)|fnB)2PKPHB0w zBR}Bi1zXb!0?M~pFGXN2BcD*tBjd0<*27mUDpBin5E0cP)UZW>s(o>LSuZIP{G6N#OYi+a>4<>*-a*}&A}N4b$Z79I2? z>bdrAm8bJH%{#(d+#H=sxeuO})9Kh3^$ti|7)j#L$dMU7X`+R?mlX#Ojr ztwsOCKmmCM-ItTE^{CF(~GqsOh!r0`d=ECYO z>^$xt)&q;hXAy(^=b<6rH``bXisj_AtW@ZF>>3D|%8lpr#|JActw)U3+UR#+3?hH$ z$Kt%gI)!9N!BwTt5yY6;lvF__*#;ZIe~=UdXoSjp_Z+r@=NKMGV_m&wo~H#Yg@gc& z4ndq;iMk*i0J#sutz75`qCgL%W@D$y2(SP1&cvntKvkHid{b~H|Keu|{kxpc<_f|l zlAabyqOjw#-K5sQY^g-Id1LAJfVSIALCG&K)$`*G3Ez%snC^JcVLsRLDmvj!yrSuW zup0tLHt{r;6OC6X2;xS%JqP5@$>shM(4( zB2;KDWUV!^TiIwmGC(*j$(Q6e!eo42xIJqy^egBJ%{sH5)WSCPlN{|=_^i-PG|R~l z=8^`_J!T$=a#eb(&1LhZa|zP4y0{$idwS}97Qw8ohQF0`thFYGg%sBC&GX5%CCpYJv{q46#KXs)K*#WV%;B&GKfaz{|&XVJazN zx(1aofOg!1gI z>_Ww9L<*eUZrH3}7TJLBaC)ck0m9PCNvW{dKm~&z?=wmN(>VhnrRKt~D%?)p&nMiiP}z#pS7} z$2m&Cy)*(#p$d~P`t_{N9%X>pAI${sFq|Nf0Hh8`1>#G!@33OVtz$3G_#>0!O_u$t zjB?cWR=at`$e}Vq9cdB1d6qAb!uF{f)LT$MK2V!ao?JEsf;$r+k`{ko3Jbtu;E1?6Bk9|H7Gk^(jryjxu;e&Fw*d7O)8~LzBO3dcBO|d=sZoxh7Gd@Q?E9riDX7*wgZ?WZh zCwhn5z=SXYsZ7Nn^oeX)N)@z~RF}?r1&m|u_JG%I-jR2)m4^pY!s09-R$Y5^Jh&b= zll;4l)CD!FI@f6`Qy~W?`@ci;nC#zD%>URi%IJt+ENzU)_hIxzX&2J2tIGh7DAh^4 z;Hb#y$UM)6`|kfZ_^Q(Xde}xja~4beHzIlvAu7&q`w5`}kPSy#m4sNAw%ADhN*Lt) z%T)L{4TF%@PjJ%VJ~oqcgP>m(L&WjTc@UN(j_nSc5W0xnUtvZ{=4EpBm@Mr=kTOSQ zCNKwxQc?K;EUC*FNbw7u|3d>vz%NkpWucW|C6)avG6&Rwgg;J#Z9Z`+dv?UvDJh}p zyB$>hm9a8I#J3yBkC1|Cfy!FVS{0es(6Lzx3489X?zPMdx8&5nSq_3wpE_(T$Px{> zU*T(NtaCi=;cOMQ2w`d%9C?OVV5A(f1uPSsHf<3CTqqJ$$JRy5#ntg|);(@UhC%0mN*%#~}2wr+e3+bH~|&$i~;R@t;k~jxK#4f#9Nr>#-Y_MAy3k5`gK39m(X^ zIUux0xf3c$SW-Cm#J9O8RGP2w)la6>t>VYwu@V;H zi4+nm4Y@fGO%3|IIwFbcM=4@!BaMXdmVMqO0Byx{RL59&E%dyuQ}3q+q1{ZcG570M zbJ*Hz{|ZxR<#Tp^GLYrgQs29(T-)tVHw8d)GjEj1XOU)6bcH^ibfHv!IW9WO04b-3 zU5P~k2*7{USdk$@>m2TvSUb*RP!Vs~bs@#=mijh(XMbNo)|k^0bJ{gX8hk7pQM=@G zh@0H4XwQpvBXf;oat9^p5@n*h6$E)}Kl4Yyw zwqfIa=NZ|q`vKP54AQG}m@SM~XDJVY!Kd{iRT&*Y79tRQLdexo&>VClecG7mBDc1g z8-s0pZ}~#<{&1Z|-~UJP`-Ay*!~5Ka%V0T%c1-k4cioErYGBu~wbxhalWx-6TK?;` zuKP?1^S>i_3-^aVaUz=74nuU5DknhO-5te<#+*gs}*Up)&e}*XT#A zq-&0pyC_mLTH|fN*tT*CsVl<7r%+Q{`{~;#0Hq2b zfWIzpVKUQC(g-~t8In(>#TJ>Rv2daKZ9TM6%eoTwA@A3k53vnDjy3L$v#u$oPEw<3gNSZTWNCeDB3aaaV!;Z zh@^5==x4s}(WwZNd~JOA>=Y~#d`vW*z-@>sqf@i^s1u3|P*yKceyWAM_XS~$*l=>5 zzP2Qs8v`|A6>d6V@9J(~RVm<`d}#BtNG>>J;mebqI>W@34v%1Yt59Bv{;lUKFZ%JA z?^N2gT|qm9V7fE`*cWzCXE8Dc-Pk&MFgpzX%Q~E-k9y18o&vaXxa-b@ya`qB(cdyE zf(butop8wT!5{Xj;XBPJ_6{QoGQ8SG3v%u=iC-CMl0K#2qR%OLxqF;O9N?IN5&%v# zcA70Cz9~})&R<-k^Ut=q&1swIdVM0@74>md15(_X<>C@SQ2YXB-Scwq@sa^v8aDpf z=T{@|f1FT|1U0Jz5y`f{5ui|$*gChaNND=VT(lCgc3#jLhv6`lKwzsvRumBYyoATP zM11nJIk#PF@r(Wj$bskG2X$k|Sd{DNZSQRi_0(v!;O^7Q)|@W5ua5x8Yq$NU3*(XZ zy8;^ruKwi#7#_=Hd8|i)ZJ4<2OWF1&RPjAVJdgAih4y~$!gz$>`5KF7kq_4e9^1=+?r|%BjICs@+;RQQ zGi`y^J=B&mZVX=2PjHelA%0O!2=+V+fOLUj>6z#Ob8CXe|D;WjqJ&)Ux4 z&r)qQ1$N+t;8(V2gQQZFt=QN&&aOc&l3s2@o4EZQ85C(L<2%jxRCFvLcup7PXDf5B za{C`8w$@s&wgEwg*~HIQlRtfi7S&WMZz$%d1etbhI{=mmxg!<&@ZD%tFvB%MoV+lU z?Um9`diCU5qcP? z%d6{g+p{rzBJx2{nyTowuyZ;-J^lbbe)hSb6EgoZpLMWkq)_s=G_DxySp*UyGM##Z zSK@fwycd?$D4yI@fd!i?kl1}{t;oUWxg)$fp^ zT|?XhHXvYh&w|Gi(_AeI%^HUXjvjc9k2zOGBQnpq1jf5h+8A_`k1r370%rA_NDprq zs{O-cj*($8ez{?%qAb)XnVsyL403&il-0Py5LU`9 z+%KFr)j#w09s*l@@_m)ud4`Z_c%FlWi~^DpED3npne z8F8QBeqg$QZ{KNh8&Nkk-#24^>U4M;PK|QrLTPD-)YoXF{p-D^QIEV}meT=hKxN)V zp}8jmFcU>w0Wktb~NWu2N7Qg)8bolRB88)n?}I%P__X; zC4Ti{ngGVoA;BUuVfYDB;1rN*g=L;yrsm$kTHhy`PM@i?WwznQHw`y6S74q^`q2wm z9K@}VMCbuVaWxS|e$h;B)3i@zxF~ZIU*n7YN=yX!0fI9U&o`#FC6bUVcgSk1)!$xM zWz`UfxYDD&{C{dSxon`t*VnpcYx>ifJxi^zz zEqH*kcD1YdxlFVGX=o-wa7)8o0njwyL(ZCToH~%DkWeE=#*NU>^^H8ql)oVOTiX$O z&YAq~KHGE&BrA@n zY_K&6{7_(a$he=2>k-#R{>&pZZb{&xRpou`UR9FD_zFU}mZ@d^A@$*})_l+-u`MIg zJx-INrg7S&?iHL^p|$%HBR%t_!Bil&=z_>1?z&#(2CyzMA-wJZ-3?T;lcLnEXTBEG z`+)}cN5rSQ4?Q2+*KUWNM*?oG0duy-E3@p_n7EOT@3_8w!`u-Mz=y8QUkw-&(=*^Ay4 zunLrb0&mTx4gdKq0v~WZ`A;^6`_2Eze*=roZ1xBN;bbFmZ)&W*?& zJ(rsuShH~&=Rp`&FS?DK?;gqB>$P6*8j7+Wdz!K6s4!MobhwS{8|3aw9bjhe1DQ=h zg*L(m*Df6n0O&0bjv+%oY;*qtc<1=Q3~S!ZH_YJkT-~@cgiEQ_Is+83C&us5GR*$E!IK{RQI2q`%mq#4!K|3x*e)z+RNpzgW=rt$kU`8P&`6T=I*8$y*9oG5-Z2~`WlqBh>ulDrquO&UjD zWX$w^*3JZKVR7K-PEQ+>ex{>|mz^c{=r1CO?DqMIP5-*@y4~5L z7GhepeMNHq4hc%GzM=u0 zs%?<+DOO6DXC$1;c(gQiLnP_G(4GPY>V@VMtaHY`Jpmx}eJN`ASA#$EYE^#$r*K7c zj6ixVQkzbC-Dlb@sC*JV>E@+M>>y09*(4&UA(k( z##K0Fo-~V&X!;mVS9*?rH#hIP35;Zw$f8K`+MBV*0GKlm3h7%a8Yq#?N~dRpHj7Q_ zFyWLW>hg9a9)KWlnNUC`@|10wz*br+4-IA%C4d*yOm|JI%p=i64WwJBvJ~jM4<;qI zY8qEKXsK{dIe>82w6Lm_1Pq-c_b2WuA*c*|XVaj!bA0?$AsCf}xD8{)3o( zY3~`IZ)c%?n>1io3eb}eI>ag|=o5XgH$`J>wOfQ@oVXhbzLbQzE!>o8iH2}YmBL_) zPlz3CohM1InB6C`UQ3?62zrxw#}dt)YaMPgZgB!jBuww2K#@ zAvSR{+gh_rzb)RjE|u!mr*7{HY;6hQIE1V(i5}Aj*~&Z~bnP+0lIpAf@BtO@LK-_rAi3>>A(_8gJ<9gxTj%sZ;-+41STvjzuh06-jY@x{(QDM zr*j|>$s(w_2NroptX1jpGx&}!O6aReRGPu;ZF-2zvy{<6<;J3Z5EkgQ`8R;Z+lc+} zg^xZyk(AVwJ8AFjMi~@C8#9fj>Zvn+gqt9jHUwx!U zw!NBb_d8tVZ|#b~&S=c{IGHQ`ZMC*L{(YggfQcn?EVsH*MgHYIqxTNTxM2rlwXXG2 zi)YcXgC5ztxtBk8dXl}rDg@B6LKRI7}p#k}u;?s+RT&P{=R=YK-9_+os?6rv#LN4$A@ zq!K)#CP;uh8wehX4z1asd<4MSdWFA~$)PVk{-y5grv)*wLJGmp5M|JtrcaIfRJ#5% zjSZwOVKDxXceJ``yZvuU%<&cR!()=`B?TZM_DtCkQVo?gX%?LUrAeu-zt*|4Z28~_ z^G-up1;P*tC?8IDi?7j6j@6a;?K@M|!r&HvWXJnQd!9Y z-vHQ*nIEk8gG;qZfc$lbLW+{P`h%aFoXV@fgKu;)f|&PCE-}4DgF?C2;0s4Mgd@BCbRQzz~_U%GB0xru4AGc~+??N`5ddLzQm1>EEXc!>TU@|}6g_H6yzZ175l z>oG1>M|g9QfIlU;KE1)Gh&~;jH1K8=4$_1~9IRIAHY`ZBK?_BK!h6dsR4g8WJxAOu z4VL%HLqun`I*e!xt$&xMVR8%@QF9-P-;$Io(Tz8|{REw+Pe?_Jxw|VXl3bG!TzGGU z>YdW($a^mEd;GoqzKM_&`PNx$JmXT9FgrV~=4EPh75J$pLo`Y<2d_dhr^TJCVkn(r z`J?jtvTGN|80UrJFd{5%_J;|VGQW1&O))k%LmI#{>X?ZIGe@cQ4!mEb;4NCwl$ric z>8d#~WX2J(wYKm1`E0ao>&<=V^Zs?CIM-(R@r$L+a?~u-G3HNyDudnAL5JUneQ&0`0ZCu;*bNp@&VY#q9xUtHUVZ2nGakPoZ3kg zI#R}#oyVbPxGloFODVaVMj^FZQu7*xG5I6LWr0ePOx??9hm=Og*`d{3Oyp|k&)DFcxEVkZ zXio0KPH>K?v2l8-EWNLj>kYZ}n7O!^*l^eVd4<_&<--JfZDpK%H$8Gk)%8~H3Yojf z@^BTo6o7K>ZL+*M)ctFYzHPbNI`xpnaYW^~_uJQPR~WxCH?KUgWiY5R6Lkvky*ISL zIH$`wXIzl7G#J~AZkW2ZKc|*`==ec}{OHwldsd%&Zxnky^5wlIvow9o?uAU#vRrMj zobF=cMsUrM)7Zip33KKNW=otO^!6^qcuH`tH|j|K{{Am=Nz)@h&TBf^u;hD-9$@{G z-pF|L^B@Zg87_(@(u;CuVe6Zfg+`B2(XN@!KbOc0nw;RAtoOrDGX%usZVtr9S$sA( zGdFYmj}B6OWFoEOFj+I4O_<&jzr_QeG;(lhNR14a)qqZ z>}2pwdjM&T%shMAK)~{t$XyeI?E{fS>|ziUbMQO$5inI=`blub*W_Wjo~NO7Aj^nk zXe3CTJe|w{a(q68Eb`e;)zME)CQz$9(m+{6#FUnZEb>mnU}fQ=fcZJL;&1C-C5)50 zU9df1FG!4{5rH4_oFGI?79N4r1#MG;Kr}rIEl;&BN>*8Nld%c%@FGp}K}Ci2r9%r` zF*SLG>S+gd#IMU#JqucOrQUE8amE|$**4Szk>Vf*$9rumduBQP7AAQ@M+XO+`MSRA z^a`;~=q<$B#wmJQB)BYFgermgJwKJ{KZVFXgvW0leNlA4Gl*n>y@ds&MTpp zJQlDM>PC(GH8SjWEm+L2kHKJM<<+b~+%*z_WYR()b%B#4ZFz|Nxc{&KEEz_q6 zGw}J&PJX{FjN#^xGDD37D~;cpFF|ptML&%>?Fe2VUv>LJez-F`;;#Vf??-bt zJDS(6cAiFtk9`;WACqC{fXkp)uZT6Mc-Q#zU3p@aCx%VB=4Hedp2Ia2P}`+w7!}`j z5+J$E<}eeUY#rs`btq5q**yo#+Ucw(vU@Jnx{$#co$h8C4I`ZX!wlhiv@O^AF&`U{ zM#xJ$YEj~R^ImFmr}rYMOTL*%f$lt}Q6xRF^z>6}`%n_yjhcqf%VAFK)UTmRydUsT zJgA&hyN7e41r=#W?u;+4w?jhR^r$5Tr`8`QeHtsmS1HLGW6MX>U)!xk5a&IS1L z{H5%9m}gqU)a^|QJx7{AwDnDOa*^J(mIu#0C-{qyoz`ij7M6{#Xndo$t|tP6+Q!F& z$Y^^pJb!F{UmW#sb9Z*NVTML^T!IK*AV+gu?%$nlqgVBpuH4qyhpvvPkXstx%()%A zplw~FN}4or*?jWkRLD=;I<{LIPZKxeu_IB$U9Hq!%JK!eJ4fTU`iH8Oi|8A1rBZ3S zc!)%2=%T(Js?9L``z7#NaFsge-PbJqnwJv3%je?5TFpyR@Boi417Ox%Cn2z(zXKgG zZvf+K#^OxB%Q$gbyqVJ1LG>Zh3Pz7wKv$ZsZ1WTA>$!;crp+$N`r{wFg8dhLm>gPz z)~?1;zxy;cehx5Sj>kQUW$k2g$hVG_wy^Le0bC7n^>Me3V(RbWWbdCOO?ELh-7(B` z@>B>hL|4l`&`=AcR0p0rHLNNBI1vthSZ&=UkUY__gf@cC*o_1H?o%y1YMnro0eI@r z#V$e}DYaPnL!)`;=5&ww=IZ#faamRQDIK5_>DD+!ob2OvIIyQ6PM&S`p?f;$rbV{- zQ=f;IfB99@ft?KAk@KRZ!Y%*z{l)tWLkstataqRV5?eePz9*Rvov|Hle-m6GM1hP0 zb|fATmIIGJTF1%uqvjcoZ=KujPHhE#`^t<36VbW$AMA^a$1lGb{X=uqeVTaGg_Z%J z!|&;vzt2XGZ{`2Z*5{_6Jv{xz%7Lsyvj_4$h|_Zh>@1;vi$R=aThLlRMd8??25T%%U-$F_Wz;VuHTw)puX{Mqd~eG zMFi;%X^@Z*knWNkqq{cRkCcU^gh&mL?rx-|VWVRTjFiC`@xAWrdq2ND&vkw||G{~m z>%5M2NY~}>?)9g&Vxf-=Wl}xW<~K`91h<}>zQ5K=;6cY)a)0e%Me`{~bop>$NEFI+ z%#PyVFHQA9+K~0mSBFzHPSj(od4)}tN(%CS=-8C$eV?=QZ%WSNm(s}6O3!4=!FtMo2y*3BGb0HtMq1Ca9$Q=lJK-=GvvOr4FvGN1A$~ULSD>Rrtq;E- zNgBxoQ^>G=-;xQSAqwz2=LJ1L#;lfkl4GJJ+MX1AwNLm zX|{>$YIpJLTwDpg45Vr$Bfea0p3D{PFkDEBYAtaRxJlrjtD8pY!TNm)+IsY|74XiU za1q>>n2JH2IWWOvT~OO6B0VwEZ}DEMS0hPSkNE&k>1!F2Q>>GJ7{eJRZJO1{3tW8Oo8WF-TH=RWn}xu@`^l-g|RS2I4FhCrhP>E93jK7wtz z){ZAB1w%tT_2a@FqtQ4{!IQ3rH`TvZv`qFT%-G!UZzdR5RjvYCiZw+&U+v&i=E!R> zbp2~@#B0ov0;E9TZ08jsqusb@wP*TB0(8t1wq%|$9cPQc&|JY`DJ{lfx_^Iax6-s9 z!9(Ghxw%HkEHk-~db2+%to4l895`1tX~c^{8Rw#duhocJl^VbX>w0D$(kWpt($Hms zrI+wW((TQd!n5kq6%l+ilG=3MGR0gcvoj8Cx<8sWI`YxR=h$nbU=7=j^Ei(F-T^(> zN7VJ)`xVF>M|a{Pg9>VnFBYP@y-!eJ8=zM=radVcmJE0zsshZTqUV?3HOPOI+p|aN zCyeLITuAz_d8^x`gei0x-C|~T<2m~_rtHo2pW^g4O!EfRvU;rcz`zK|5UFv9%&)iu zOVH@X!`9DxolWY0(QgP&xe#Zv@sP#}3V!dFvZ&w!=-pv4-h4_ka|>Q`f?siZ)DKdJ z%H3hsNK@aMk=<>88A$E$O(T% z0>%=%}N2$4>f0Ud%?HwV=aX zu$6IX9<0f%P@H_*Eh3Zrg^wZ0q?Y)?EfG4xUZ2C{IO2ks@lCltjtV>Km&a5C)H#Tk zMcDLQLGKj~!uIh3D-eSky&4WgFIB+%vH1HcXqK2evA*XEai!ftU|b^o6QeEG$mLv9 z(!YT~e01_0U9+a4a|o^ACxId+9xl`C{R+7#urOr@R;H^n=LhL+?SKh?46w1BxY=wb z+fikc_yC9pK!o=?^2G=dm-5Sos23eEuW=gk>8qMT^rZ@)RrvwQ+BT$n&Gz{2A5^OJ7{!lNPpuja9;4Lt)?KA*Y*YxC8ccjgjrmxxn}jr}1ag;yF^0mK*eS z=X4z@mV}2n+t3s+gGr^Lp;PG_#RJQiw2icYIjfvPJ^Ef25j_5C4e9D?Z0*?v`ny|* z?%QDPL!gYgjIJ&@MuW#UsBV@Dy) zYd3alxCQVw;7Qw?Ec@~?hegQVrGB`|H@UAK*{Q3;J>9qNz9Adro-$#<8aRdLm9yi+}AuCJVnXXPoG|#IRs%3hV_$1jAlk?TF-D zZSsd0FtHMLmc(W(4#c0BEP76K*`y|Z6yZqmQGW>VQ^!B6YYGkcctt*G*ao_J1Jol% zrrhm;e$Y(Sr%581hH$gKGp;tY)Gy{Zaxi1@eRbMt^LStUStX>s__HDlby`1;5GU>a zsEO2{wO;%Mnm4>ZJK@M!b;Z+(08At5eBhfEr4R@h#3b!TllWbUW$IH`FsI0LSF769 zN-R?QSIT2$_4>`)>E5XQx$}Q>2ESNqM2H%P`v2?9qGMq2ux4Sgrt76ye$zH_;n*GG zREHldR8r!Sh38MM(DHBfiiBZMXY|9pbWn$g8!*ZjfHA`-9#yfsW&fKun@mA zK@uniX2}gp>~qj?5Ps8}H5_4;d-x+#H(_{8(FXtjR>8x>DnNyz>3M^C;he>%W7d~? zF0~PBLvFm|lmxvkYZNZ)Qm-xwL=*V+`FTiy1$ckNWl{*!3Q`Z(B}g}W4;Rm~N!JVp zSi;KBu6B3Q50EcqX^}lffDJ<3Rr^cCeHy}BtXH2tFD~7lA4H-}vacy|&nOZ;Wua2} zJ>>MxS_3s^>N7@CJJyWq=|Z#qJ*$}CBe(7^E5O67?gZdQ012s}&_7sx`rbbs4w0>j zLJ=fQrfu@0x9;>GA|}5r`QRc>y2l5j@bA=d-c~Ov&;38#>IB~kI0{7`n7{ri7jT7M zQUW<3f{SPLqwkl1{v5#3?AES?#?^xG6JabyIYIGq!-4e{`CY?*IaYn|r}BEm>1j9a zB)x^V_70>1;eQMDy@Zb4U8$>1V_o0fT?E+!^JbKz6%tpJR<6ScH=Af=E_U7@?xNg) zxaVaBTLsf03c8+FEhF?bcrEsA+olO5n%Vi0(U!zB_v7}rnKph4A=_t6jt@}On7|(0 zzdJh|*9quuM*#Lwx9{3N`n${X7)-#lh|a2Vq;kf{S=i`5O8UJcXVWK?v)v*hHtt{g zxV;{Ql!c)e zzjxPDVS|G$t0{$H8O==pCX&P}Uv-hh}HW4Hpur+2$H5&i!X*299a%ZLWF$l%~Kf-kQOvz#4&)u`kqD90e? zN)pE`0f!6irmCFjH@#2|Q361*U$0yar3VM?YA6Gu{wO^JPfaUla<1R0$S5UtDT^ZS z@UGfBptq_uK1ftL?$+-jDOVYJyLG*rc70!USYnB{d~DN`G1Q}jP`(p6ISyhh_{O75 zoaDv6@pdOpG-1rXd!&D;Z&>U5`!Bc#1nav{>r)04?9A11hS@FJls>6h(X1pd^j5}9 z&^*Gzx*?$UOh1UD4@nOQxFR}8rI6vIiav8(sJMSgeVyQ&$IrR?$12premx&!R1`+u zo0U3bh#h@VQI>yB@BCRY9u!)B;gTZM*@8x4FEqEJiP$7}BRzH^UfiIuFrCmwltGZI zAyC2Q0sn%VxMpQ}u$hvfXP^`5kcZw*q|6av;8Xo7hz2vKyN$&V%Cj8$xG33Y4@#kWV@ zy4VsOomGQm{S?GUDy*8v4*Ry<4k@P9*R7wbmz=L&9`1I+=6bbvlyfdfwjZ}Z1A34{ z)3)iULzhe$9sjCb&~|v9mM65Ann3O_JT>5x`({9jucm6LKdZr2If(~Mu(w z8uKzm=t69JzDa`Tq=C=Jyh(dJ!pQ;HM(a@SWFRH|U+@j|4&%hdvC!KX>#FF`?@)|S zNKA-Np#gvaV;U?eWjXmBs!7;B5_9M^ zv^Lhl|5Uz~ykO!5DO3-Ua%qv-SSi!ayQ*hvn+o>vseZG1!kvcP(ACWx?Esqzyj)df~8J)Od0_gSr`7D`A3I1Jw()#V~ zzgLT8ry&%c0&^f1K-PPQMSSnd1ol9@FJ)GgOieIEA?O%3B=)6O(FD{$QMC#+KGOpb z5lC?H34M^_JQYWLAxS=%ojrR)%nBjM8I8%gAw-w4i`nbve&Ei`yYzsC8#k=_N;TO#cS~FSQcNg$|IDJ~@@i;9!Jzv(!MUjd8n)}#c06od z^l#lseBPLVR#5zB)bdw9Vs6G9-~2UCEStfu=mn6BI52XnZ^ze2qcd0x)`jta#~Q<} zE!{GMqDgE#7}rv6=BZ)O;dH93wt>}t6N-j7l4L|JamI;Q?FySRJ8D2d(Ecj%ZOP@Y zBgNnh19nL*3S>lxg>w(D4D#xUN;k7Q+h=5LSp)g|9gbe`{GTBfVt9*07mT8A-M;C~ESwC}6#U<4z#YkuPf8o7JwtDjVuTmt*hU~meCWs0dy`}_Z3|o zbp&O!q`ho-O>2EZ3JUIh1Fu3R%Elc&4TQ3Sg-%>Ey4p7HF=o4w6BpbR=86e+{n+(@B~F(qyM`UoUyrwo zNH;6yaC>v^%_#kk=3haCb!LC0&M;m!4|X=dBX;OkKW!1)Ef%&z{_e2Q4 zLxAI?CcX1^oQy$bq35&fsB4k*LHY#ec_n`1D?C1hw|$P>o;4fkF&7e~o4g8p|7NgW zTT!CXaFzAV=Y>hxoHXeVsy9i6cVFfTCD|Px{=63(%*Bd@neTpssw-*$PqnWyv+N%( z8wz?cC)xxX#os8QH=j9wp^OmA=5)L%jQdyHJi2;9dnyr0IX*oB3mN`E&*uWW_katd zZS0!wT9Y5KV(gt?1X)Db?Z@U3b6Dkh^y#hjZD&~{uOz2xL@ag-1#x(|y8kQ8{*!bI z54Uqm7ed3-srYN^q)hpa+EcTDE98DFotwqr_#yyxeai;vZogs;y>v{WbP>6xT&RwJ z8lN4X)GS?=@Gd^Hw3J`^6i@*4BCLPTHoW0sD3)0Mh5-K%Snfr51o4EM=f3R%{v>L& z_v@_bcxw>j(|u+ice3O9}ZZa2t2y2D^zywa+ z{=GBKD2DTpKb1C|8!XUqh<(|w&hJ-2p|WxQrhi$P{#*Qz$I5e>J3&Ao zOI30;yQEN&C1n=BgN15Hp_wS8P@W_P(J@nI2r6c%ReKxAQyqmZ^t8I@FHSphYko{B zBBr}rMX3!wj zO(sC*XCtXV7g-a!aA-y1UYH@Z7fg^#@TLG)AX#TJ+X3J0BDbbXB3zDc@R4>-ZA4c&qe%uG&_0~TR- z7GBgb`hnq^_(AZZ=8?#L4LYPV>%rZ*s>N$UU3s@DS^_b_Mi@`S6xTXGjla86PHs*K z^=>w1QBLl0&CdYRLbPTIIK@5%yht=PmNtqEBYNe6Mbw`(zMIHyOFohg`rdgu%-}J- zuFny6tz-;krra+!MM!jG!;JVkHr|k(P=dSJ|6W#sr;{$QsG9-dTK}_q(Vs0g-EENp z8$L>%ComxnvM|aBHtcU+FztmGHE1!@L z`$!@#lt?my8%xRg`Qk_&A|k;LItb^7@l@zT;O4c`-*}N(BI377tys=O+|8F;E%zjUN{*HGJISmaIL8~o56)y(g=bNB7& z`akSYp36~O@H!?^>l|B4GxqPLytnss&J?4a?>(U7@78L_UPk740;-^l6#bD+Su9#X zxw039DOT(WB|HKKxktg&*sz4A5#24y2m8d=_LKcXODWtisi!tPoS8^XGS=A2 zme%Wx3IAt&wb|qZ4Qq{strEit^8J(YbHXazT$sUp(j5v?u+#ykf~ z#rhqk_s(iVn^NIkm#ZJm4dX+<@@czufDb+Cv&2J=PzZ}Dp8{pC_iO=!F|$Nq&t}!R zM-PuhPYw@1(pQ@OdQhk{TWxm)Q^2%?1Tz}oj|j^5?>qUvoQ@Lk7kiZGX|KK; z!mnCGkiy1q8Y4x(yEMd=-!nfjVKp_xcE&YW;KZ7W_WX6Mjzk>8K^D&(tBB&UcA$H& zUUy-$&9Ey>^SEk2*{JnNr+`#Y{L*v(-6GsCr2x#Q<|(?cfPf@H+h!9;j&U7JT=TlE z?CZpNZCmccH^pc}SP1urggS-n7m)VOI}9sq@LPN9<5-q%{P{ZMyWr)hL*XZM(y)$d7Idcu!r1~?hn4}&IP_d zoml06o0n*aS>CVub4K&p6`+Us;|4NHYqyeFYw%o7 zzbbiPZrNj&##;zXM3>;DalgQeMsbs7?BZyet?3Kcb@*_5c@bt%!IDj`JExyRQ#XBbUrzLpTYO~T4$yL!* zxP++K>O8|xv`W7U?WxOu=9#?1O!gtpVR?1z;B4i!N~;Mc2rqbGUyhrIib-ckaCwjh zgfp9|A~{msTxa>H$Z~}jm{aJRjG4yot2)u`9g#f`S=<&95Hjx7i8#y?oll4Pp<(|` zD_u1nNx9koSLEu;AXv~)^bgtT^0{i{a^oKNTdLT+I$EH`wEyv*MtQ3BJj?358pB%R zXKq^P$EBMRk^|T2<7d?2y$>%bV(In*W#)Ydt5rdQ)DLO)PGmc0P%iw z;F6~`CTu9g`G}8X$R&WDt~b87G4^L1d7!%dm)^$MQ3eYin->-w7 z&lm!yqEv?1T0~&`Fm#zIpCilR6`^~$F`3ND7xRLWOo*_wk%v`Aw_h;AJ1!5oT8*4vh9r+Dz2Ty*X z7Vv*8K&a)88RS!4!85)Y%ZL_wEZtD>?W=@tEAJi7LnMufvBzuhCEM!Dh#;5;S+!Im z@Pq36-_aQ3mPkyk;@(+LS0VcE!K;r391&mhA~4zKW8=EJf6EGH6}&v8f}$JL|JGmL z$%whdzhz}03M_Nz!(SZ$>vBM6cRc{8QL;SV00GK2yEpNXM1~uLB_UCGo6>aWDIBWO zP**&E{i^28O4hSFi;s&$(p>p) z$OQ1O#d6G!pMrs)z(*dwI!E-6kr$k6_rt-F9ii=^?T208uA=i;AG~in&Q6AV{(qGh zQUKCNeJ^yNlQ;W83u&XR}#iG;Tn zj?l5cZr39cV_k?{#-8gEhZwoxh za+!M25c}_-(AEpx#)y3!7P(`fP!YU304Z?afV7yi?x{{GGo8GQSo@vd!w(Y*yu7(M zL=}i++J)DxdTsb4(Dm-WFJ7U1iWLghYaVFPl}Rri25-;7ql8E0Ny+x7L11Xq4YS+$ zg-B;1_E&p<2r@YN_Vj@BSJc&pvKJKp3MBx;!yIr!rrBFIzSoM&Mu$bieU<#S-YHR% z%(Z>!P3!sCj9Tviz}iCN14gKJB(iO6(`yiSAo=84=u;(FN{gV1#dx=wWN`WYFnlV%=(s*x(XIkLTH>Idjkj1d?Tg_ihH6B8QuGQGnu%Q23o_bl|H2cY6bFj%p=5QvYh`R@|;`vh&sR>|I2 zcAG$B3all9Lh=a~3p|d7^|RuacUd&VUmQo}g@h*>Ij3D-K5y-bJn1wjdML7b2zQn|pF9<=&1`H2Kn|M=b53>3CP z1v_7mMdk9IsF>m^!9HJ>zShj#d%&W^gxXi^#Z-1QVK!?1xg&M%FCk?s293VnfYV3n z;3F@owT9IU~-*e*Vzf z&_!Qk#GDr14+#R)R6(tu|1F9fRE|gD=b?wfw8-jw1RVf{$7e7>@i(*KtR>xbcHis7 zYtn?L>bkA0W{&A#^9p$eOjPY1BJ5HH$$&~~-QA~;L&C6{Djwy<0e*tJ?gE&}5;nO| zgT3Zz@qpDwyU!1p@VuetqauG|-y1SytPrMIU)HAi-CE!6ANtZ^lhS%h7b%uimj0^I zO-b;S%h(#X0h@aGlsGN1Lq`629RUqHs5JP10lmo!e9$%#2^%Z08*o^DMOJ%0^6 zGBatVr^holiDV+(TnjFEet~%yeD|d#UUgc?>gmSaI_2#ZZ#D3d%O8;%l6e4!a|wY@ zFnJlEd2Hb=N^9=`(|FPjHo^<-Q6b-SoI3f|V)pCg!8h|-D(xYizPDKM!A;@tr0_hK z^st(~7LQX?ELShATak40hm^low!K1ujN?e?SxNb2a)lt0a5Pn?z1iph+rDHX0ENFp^>0MR5` zWz2kFfR7DbqY>5$YNAX8^B(=+$ZrS6iv#FbD~ph=7;U`9N5f5p!z!!>K@~l@!OJa! z8#O)>h7%jBPt*fw+aIDQB6bQ_I*%1ui6+;Bk?Z`i#K={_9UlWds zn;$BO@+bjEE2>G3B>FDC>o+vnpX!J_a}qCGQv#%;QA+{CUlvy&fB@U7U&%W|fIzIw z7Qdshz-G9g-+zrDngB8Cj6s)@5>i?ZdRt>#0tZ*R!5TrR<$5@{gg?w!RB=+X>dx!qXYvpBiW9p+Q=t6S@ z8P)Q!-_A2fBeh4H)DAQbT~1&EuXZD%;P}^^#bNf6dC!!)u8lus+YWME_)iM57ed0U zb-Ql=ek`dEk0Nu3{O_3reNl?y!uP+U%pfC>8Ayx28Qo9VosTyfe!MjGq2^l@OEl&9 zdwPLA^PX-yJDX;kj1K(#M|d&5r>adN=>sM%N30HWY{MY3#Z8{u7JmDD0fb6~XSHcc zcWS7P<079~rTf2veyCMTL{NKM4>3$|VZvmN1{4z17;9VX<8ZgO_=d+eDw}KDq^bB` zR3$*L$3$pTV(x}6ZC{08ZDEb1&c`*|CsRLzJyfgxfD^8Y+y4wXR^KEB z3~tlIuc!r5@rD^kw1__x1kb#f{sY3FQvYVfZIxMa1d9w@;yu0@+*??FZiWo?-}#lw zE0h1f>c2ItcM=aFLwQZQ8J&C?H{Oc=#&Xrrqt-XHy+_5j z&38&R>&vn{``;3-`tHcT68(qOaFN-Ha^gsPmj1Kn*eW}{z3GDDHa>s)Jk$PDS^j-) zHGGqebNbGzw$w^U;7U6gIIEu@QauBIg2klc4#Zd;sOV9cEQ=7IRIyNsvUI z-Sg`_1sgb&ktM;=n$v0ENgflQoc@<$B^*|fty^5gS~?EGpx2*EJklS$}`^I6XVS$IIfJdl%=NX zhd=vBOqUIap@szwH#C))_QMhYkyF^_!rXw_~T-@c{YWP4e&k?qe9xR6$N7Jx!R0(&`oM z%k!?P4eRtyt{EOCbRmIkpQwZ4!pf0y>~wI7M(o7vPG0;b(dthFusKK-drFTfdD>Nj zof!R~5nEiqONq3}WsC!^+j}`meNPYJ4ZqHA2@6Z8)udEiOUdaQwQMK+5sGyhF^G!# zR%MIhnD1Tzj92ZXMD;ns(%mHqlVDy4uBIhyeISy37fH}~z;fhBEwuT0ru6JWP&+Kv zY)K=5;7vkKcUfNWPh`L}bU?FRBTe>Pb|s?VZm+FJ`I#1bl){&>Ar=|TyL}q<^Z+O1 z!+9pIju>O_+j9KXL&9}zY{^~|p$~l<|2=Euec^2qhy(3ZZ9m*VPWFr#DK}EfAORL- zCG(G&?a+Vrg+aZq$8@p(w-(Nm=zpWe@)V=uELncbO_&Shxy)PO+hyRPxUzbO`@y?anqmUoaZpZN-t-k$(+kB$CO(pPA4 zMt!kT{ebhgui*|h_F@_>!=Wh-rMfwh@yVZ1{&)HV zyZKWFc{xnP{J^<%C^5u|9|H)EPiYh?$@xNQ4K{t4iE%bbyWb$4Q{dBsy?Z#T+27Y} z(sk)FAV|*fuazM*{N8_B-D19_sK2hXV{aj(B8hAHF(scf9om&Ky81)*dN0fZuzzJ* z*wkl#DQm(^^m^#tQ8fVhZzaN=uwxz9vxt9d4ui^-L4wtwvJdtF_m6B$8 znhzTbh1ZdTZ-PPXrUPoZ9~8+?#b|ZLUt4VZN5pQKR+_14w6Pf0FV>7qM7Kn}ydK)9 z5Ooc7$AdtMJ>tMH(T6Q5kW#-xdLK>mx#DvZO7$pRLnHyK<8UI*Sl6SmtF1{@r~3;p za~rGyzju+8WpM^_T^2kuNeBpO4zA#7v{F^?tGI*#aT8Anqz5d_5J`6#RJG+l^mc}p ztP4N<9C5;r9bp%HI8l=0XUy}*@9i=g$?cRp2;CsKS{wfILn z!eBaQvf?@;j`-xzsdhbeUAKNWw9%=ebhW}ABrrY$S9JmP+hhTL zPhb?z8<&QE>!U@sg!`(JvYYHgFN9dJrPAwm4`(wbj4i-(l%eJ8aW_H2zq=rUuHgPy zsyt30?^XkRu#T^gvgS(VIhjz~s)WqqQZI`lK9jW|L2dn1>_P`~osFnNPT#etR@-t> zbF&rwKwBGu=bc`{i=9ugpT8e`4IoF@7#k-?PA#qW$uT-IiJ zM9KgB<5h*A~y75$;q(yfknJ3-;1(rLKzo}B}D(e!T3rzSJ=tMKQ5>A0KV4;X5v zAz$_54{uSTFCX}_oXBnXNs^c!;>#@!S<7#xBfNZYKidyTu?LoJ@H_9GEc{iqKavp` zucqdPAS?7ZuZX11B2Y|!IeL5WKY%%og}`@HEa$@DtCrOjgOs}^YmiD$#7I&9Kd@VY z5bHXWQwq7dbD4N{Gq!|Bdh+zlZ7R=qn*_Ge@yrKD`0tx39p!K6uk-QryUTZXlQEHx zj*`w?$p7@+po)m}tL@hXH#);~&)L}fZf6Yqazi;@HTSSLB`OE(mhFAi;>gey9thPv z|0VP3qT^m>Y0OPI;!7T$3+~C{<|PL*80Mt#D$;Vv5)7b}4)JAe+*kx-!1{=8=%a(^ z%Bw)NF|go2-p?6tPm#VO+kX{NB}<4Lq<#j{nS>(P+pU8*vJFhgtFb zKQ3QCzq-y;0yzjoh_vw$uwHg-z44Foufgh;&i}@`s~*WvL|y(ZIyXtDEk7J@i2%sK zVsY$9ekg5BJ%MI?Zu1=+c6k6S>mz+ZE~=f;YXTg2FD=m@-kZiBCo=#@{LQc30( ztVf(h9?2FlIsp?rh0r%Ud z0Pi?bi;P~<7$D3MZ*5_?0G15vRRlobDp!wdf5nA%xk7SY`c+$+n826vQuOuNH=k_g zsclk6M)N-Huib(6A!)GZeq>av#Z^*(W&UE^uA=M(5_{_D5j!KJNGrX;@l<-`FJ7ZY zPeZi$O`KsfE9%ud1HOr?^ALD0iP%+MQ-{qxTG#L@n!>BsdXEy?YJMNO)Ma&*DHYw| zvGM4G4xfQ`r4+0JpviXKt{h)$4>IKsuc$)9aZ8w5Q{jD$na{LcBV>iMl!cg3pP!|~9dwfN@6%WWptl|ae#Dvl%`YGdO_76FSF59YvSk*UE^9xgf%f-3Q+Ju?+}!n#lmyG&2X5yU zSD!vsL0}6MG%LTVR)x7?z&jE^Ro7_y@;ht!?Q9Zx_q0mkl#hagWV+mX z5cffsNROf_n(;|1N97*mRY6Q9!5O7afWFwDfxXP+ z^l?fVCBkIb|DKmf_+XQag3ymp-=HoEhO74E>8a10cn~8T>OqCzbaQ6_u<3C(oVj+N z$O^5jJ<7gH_H3 z%>Mtl-b)$eyF20YmNLcDFjRhWu5#OX^|Sp^q-XjrP-o?DkdS>n>|%>ZX2HWz83&;BlYD*;rJ`@oM0S^3p>65ie~68{k&TG= zBiGo}{o9?e`G;%uZ^~Pj)CCG`I-jf^Gb7)v3(D>_&fQ@)(n7^Wel}1o<`z&Y{xg)j zYczIQBdDhk*6a7xfn`sd&Sy^8v)o(O+!>cg7^x5<)nV}#fu`rtHN0Aun+VK9!3=LlAC%Z>T1np{}JBV3AO-tv*&nw;k}8?_9HT6 zb5}+eQ_9oTp|>7q>?I=k`=Se!bGNL%D>|+F zf#YU<+B&as=|18iuqC>icNI$M7NR_lUGdA3g|4)&V(vGS%mzx9anJUB=Ab_SMX*PltQy$^=A^oFX=Y)~Xe= z3Z37tK8Iu^CWf2Rzxi*J$k7E`nhJQ@_`d1ubf3?NAFCtY7aaQ=%AeCbSaGS%uz=C% zfL_2RD>5CDNH7!=w;Y8lv}n1I#&C&4`S@Jc3`~Ioq%03_)L}=p;ZrGZb@)7w3N6WG z^9r~>e&@UYP4R;NFZyr2^}>Dmmb~3UPt`{q+&=LQoSf_1sR6k5$=9k77EK}7SYdu9 zUOhhbY6QfyW8(fTl8nqD=258br9ehYyon-dsKz2l^QYD23&HkW08>m;?Ke5j`EZ_j zp3cGM$AYEK_ROr-D*BxXIz~;!n1ixl5DQI?$C~{lH{1)@QGQEs>%wm5J)LTqxwQOx z$IY%|mm^z9u{N~%61G6WatT8m0AbZMO#GW^UxO2R82~tb2kBqnOv_rTX`XxbaRJzc zR^4KyzDBMGGZHPNxlDbrQFjsYaVIS=T_ROPvNlYW=MZty$rGa3ZD%D<#cC0aNcvTy z^oyX;hhWeJVkN&wOv4SR4Stj>AsK$9PNAeC+;**&E#{mvzpyZ#Dzo+&dY9}+<`J_e zI`X*sKh`V*K)DHl^`SR;hRidPg4{ZHe$8=TfXymX1N+J!=xW>NwFdTT*q8}ph+%3f zDnQLWbECGEKw(Ri@d*`Z?)wV{67}qE^2==AKmGAmf+p^GGt>PMq!-TT$2UQSm0Bi` ztu3fBSjwG^#nnjjNeW5g-IPX2IKj$e%jYxjbAIi?!L_k@D-Yv zrFPxkvfz%q|DE1VW`X!V=4E=Z{l~;aLQ~Gdq8uKT@)#6+_=|7dw;;sQMg5k$QhKZx9vou#0EA(Q!?nEMR+&em9-;cH`j&_3e&0;4I{9 zqpiE36}vRq;~gD%0o}gSy}~X(a18eZL=u_EueRDw_iNVZmy zzR27*sBM)zGt+0W+FfX5gLa{^FaLVQ04m6<`uEj`=IaEWJCpB`_P#v}tuX_pr)_Pn zB?^aQ>;4Gz9bF1H+J#fk=#^|NQATD}TljAo;lClBXb9)@!^H@DCCWJAqQNgB;L_7V z=|LxbsF{L6o&Sl)z*>AxR0=s~%Ji6w8Mf}#Vo0&vL(%y=&q-qg#i0{0M^9_3_ViwU z#Ib2mfbxPX*J8?Z)wi{11mtMt>7qho-OjXDh2fo&=MBY~MfVX;Mb)aS z;1}i10nlcjw2zn9d^4oFDt-)&c0|x2DX*etGaak)3Glz&zn=)#_9uH`K3Ai1m4vvQ+tK{XsE6!q>W zf{;g&b{uqRmBm8%(q|^iMDBy(y%n(DiuhhbkXw8?sFYrku2-ygL!lUuM)%TzWOBoi z%=Uv&l=T}IGZawVar^0Cm8x>$YLIO4%~!7XW1g!oeBu@$uf*swLVr4e6V%Eq1PM9HJz(kXUK8$h|7~y`v=Qq*)ANw2MP?Hxd zt5L*AD=?szKPGooQP&+0)**jdLp$aUS8*iMC$5g_dtj|-+i*{gBO}xG`(_MZg4moI z+8S4L1!^g@PHk1~Tz$a9tc|Ex`PkG&vB=-v)$oXn?<7m>db;ZM!6ze9MV#nJ@Y;*N zdJ&o|W&{3|Ce|C#1{7!xk(oB;-4tip!)R4meqZ#*-h>$%Xb6b?SR~Pjhvf7@pTfuf4!t+);+h*tRG?5c^zjl4s@m6gkZz z({SbgHZYAR-^qkOAUm`2H$DyN0;27i7O-`}l~K2BQU%IK*pqQG#<6+ZGR)!CM@)Ju zt4wMC3-3Pc*1wYk#ylcZgZ$>Mx+2x+kP9L1_neTbieWV4N&4ok|9L;{Z<&r9q}BNo zI#jY|U^F+n2h9vMVMC0FG@4-_?ryzMA`%SLH7LBZ8{)>30S->YTn}dnb|vaQeeF`8 z>0rdK*7>KF;_Hp!7491RH+~U2vJO0_7l(+0vfPR`c!4QbCBAOE2!+BeuZ)cSL7`4{ zMMXS;SMqCG6QqmkW9<(fF&+j6nVmg;T`@n9J^(@7XWf1gju2@gQY9J(NG)Nl^c)DW ziR;`zM+m*8@YJGb!@XRVR|Si)!FoBi&!;8_HPUsL$)j@!4PVmx5~`SLN^gqH|5v0f zeXmNMlGAGfaw}%=l~uL|iaxlYTy$F%3^0$-loqUs;VsNl&#~|yPbK$2+_4iD-am)i z$Y!Ki-|NL1a->W7Tkc4ak^XX3>Fke|) z7cqb(6SNnu{&@fS&TSK3=d&mWx|_-=^Zc8_NYB9SfJPg#;91dJUj)Uv-0yPhLlS^F zQSu)A?=2amOvSGNNCeT>Az1gMX*r3_+#>;ZfCGOFFvhxqkdXNJrO>9gm8!ZJ5hTvmv`{L~!>6w(r)g>eh6|lW+z~W!2 zoiCUf=6WiwYh=KbBpI1`^;d9o*tgEE8}^D~9$BC$Mym<_FyrUMVUpeuEOe0s`=s*u zy){UmKi&g4iRx&Y5-w-C{zoS9juQPmQ5rdy= zts&iF43b}EYd-atch*O?Vd`+V6e(IEcg^biydh8s?!>3{aIUUHiT!ZeKJ))$<1C+| zaGr z%lQY+%$a+x`aTDkGsx+rjiIw%Bnxm{#rtUa3S39A8}T$>lF^G;45g`17Vjm1NS z-!)4yoOGa1r0FJ)*K!VXYL6KxC+H~E%IUM~uRB+<<3^w;TD}ps)5S7_ltb=sy zEqOs+i%6Jhu<4jr)uAG#7Wf#$4D{h$RWq0WSBPg0P;SaVq$0#f zn_B$j|LpmE8dru1lt44eGr~E{AM~)5>}J3&t_LszuL!U1)pc+b7>K=8RvRK#(p~$Km29pyeIZXP(jGRC%fnzS*%IWIGjMXz4Vmz|=>E8iVFq+^ zn%#_&zHW|=7>S@0rauV*`3)zwfEHqfg;#x&&zdmH)GJMbSHYb>U;}Ut*U$m{vw&oi^C)>~4r()R#pY?*C_DCYP9-MyMmk1On+Slg3p)+^8e5 zl+Z-<@Fk_I-xuX`7qPG-I2if6`Id&TLnt=#K}Ko>ZJ&qm>q>(h{SY2tinvI%p{!aa{AQ2(P8!1)3GpB)aA6(0eR|#0w>+GUF)*FEtCKu z_;`4N8c6k5zBEU}i%oQIAo!MP=UJXaDRvcudMpB1;=cWroq38ULFQ>rC4gR{oqbRF zH|8!Jd_FG*U&Kk2DZMZ=c?J_E>A&v6rTG}>`f-m*q3Zss&tt|mZt_9$v3J_zV$64N zt}=<5rspG4lvT24keNOqHz#=IgnhUb_QhWoHhNw1p2|%>#HOpY&l3wbMnS;#@)Jhl z;MQ=IIjLFrLxeh!2+h@S^kuupkG(!Q<~Avv^}`nq>f&;e&_Zf4t(U?{Qw_Q{;<%dS zWlf4~nVih(0rRuE!^zwYi{rptm4u#r{>7$7+PDuo{O*6MJbF?l5`1;LSUAnhibMq* z$2s#j0u_OPkp`E4#h@_rX;Cc4&Xc9lKiD+<~=OAmfpbk79?BR|I6Fo zhA&!5f%J_#f(7q__?y|J{3IdzOVcNJtWu9^qI=617DV^=1CK!pVhln0 zXTHagYv3neD&DFtNy!JfaO&BB+uLvewKhqAQYBUcmJ8Q8R)*ni*%!@?>;ppda|6c- z`zAp_D=o6S{_}GSLG)J;b^LN_&Vm`4d2vmye%@;$rEe|!52)d4@gv8$Qq0kkFFL5d zPcA-!Z`V<)TfueUq%c$2(LHiC?i<}xk?!l>+0KVGd!&-xCmpU3Ui0eWe*zi;|HctK z7z*Ar2+gvPQf=i3JdrG)NsEQ|TV^fT8v0bpV(KX$u?Ee(*kjheuW7 z&T;<0>lh}oUuD81GFiGaXzLZTPWg9sbK%Udf9?3t--Yq%9;Z&Jf+}fee4JfefS)-- zIp8|n>Eu}TSDfo-QRKV@x^79Xq^sqP87Rzl-b@z7QO=VDA`U*>Cc|`^ywR8!H{n~< zaNAj8&S$zG)pmI4vC3p_4`-=$jjVd>i<_0ARHLLHqaJ_&VLjpfi8;d(J_FL0S{1P{ zMRRHMIZR!E(@Q?|e7Ro5y1M7268HTm79+1TPqOqI6>pDVlgb&=RL<}8=)<%XmVxcV zVjh5Ue88;}^24CQO-G?+!m`&Xe?uM-o^B%fls5)e!1*;_zbi{(`SCYoa$wvWQk3^OM!U;c&`q&IsC|+}-{xXo~^_Iv=b)CS>naqL1p? zj<09)$fx_BkUS~QQdzP%@ANLjrrg$h`NKQ+-oz~g6q6z$^=8Tai!p-g+s>|Cu@kZZ zS8Cd#_P%XbMGTovgMrDzbw$a!P(Hd|G7H8^(}*eL(plrD=dLh`c{4Sm9(~T$XUOWe zwCijA=jQ#Q>)eO^@$_%wyh$|G=r;)GucM3CjG_mgtb>1;pMH9uc81H5a+ksO{AwM1 zd7kAm`Jb$!2azZmz7!i8LEhDb*p|0eKp7zlAL94dxetpl_?Ior-W5DwV9?pSEu}%F zg>lFxsmPx{ZfeQ)pbUWZT4b{KOtQF16Yi(sEzpSvkTh z{M2^)zwOeSRR-^^rPxyFYi^q8Ab zEkyECo|cy^RCwEd;*~A2P9vZ(>k;)7m^5dCGrX6S#7U~Fd#}FijH&$=B^T^<(4Bi5 z5v0k{>?91p zK*tgq%6QU%n!FZHNIw5*TA1_3JLyJywl{t_iwuWF098%g!LkdCoddSW z+YnsDeOaVJGrOC59G#b3^Ik*e)m2GoYFXc>1fP(y7MZ#BYo3Z+J!xixy+uh3rwuCY z7t@=I`Z8LjFJ!qb*;;Th4Y1P>%qrCmSJ=9H03h4XpVUuK$5c?&@f;(j;@~sBZGh8c#|@|60F)}i zn`UlM<+>6}UpeBKpX9ukSoIghVu;~5WIX{oNB{y4*p8jnLn zJ%n4QjqaO3NTVT))9ouim3sQWl(JQ0E*?hAxmwa3uF;B(tay{|?zX-!2xIBG0F*;o z<2>tj4m9xNaeA7gF`uR}=HbzLTzjn(w!j7FPrWF~-=R3;qF-k0j0h833b$B?Eh6Y& zDkxXVb%uLy$Z#T#9wziYDfxa~4w$Zfjc>I(`6@0c`1&0c@r{AO8B%lMgD}R;*FwzJ z=OGTAt%bPX+cgGg90{)rtug-W9^B;j2(vyTe|w;5+l`gMm?BEkpShSXw5W~g>)?qC zUHX2Zt|uycdBEa?2sQlI(y( z?)*%oG=XWLzcT*@+tTg#G5zQy)y;P~^Dh^a$%gBN*gmewajTkjE7{}U(b#x(l{D*Q_DCYRy_Y~?gt-YeM;w{#+fx-fsRL_BS36D8Gmy2l3 zS%s+GQ-a?E-{gsYz5WnHR}HLor>3zBU(tV|^CVVFLCE=Uwk;plss5V!qXOW>;LX)L zVIpAQ=tu)E{Sujzf`(wXdn(H9rPRs6R}M;ZNoI`6xA;P1>Ok9FDrP=%gau&TP4YN5 zmi+D0xYKCz3iWPju)CF30dh@9NXX&YMc!p4cKg`Ki0s%Oc?n&de~~qDu;>rGf}A!pSXisnW{E$}R2sv2tZsuV!#_r`(y&ppJ3f%_+WN-i#vP9f3c zWf!zf+KEcV$V^Z5m@^bG?kQaDm_vcV2Uc7p#Nl5+Qk-x6c_+hlFeiHfM;%AxTk0O* z8IzmC8(MkjdGK-8arzTjJw~9Pj_ym`9Dkcpla5Q$eJKAJu(P(bPzRk9Y)rJSBr?1v z<+=UbV@hss_~vY@#;)MKOUs$A|KA@2=-Hh)ci7_?u)*m!D4uPmag4hp9DkPM@QH*& zpvu?_5v+NuSn?^_%2T$xmk-DNSfBat@$q5u*ES9|)5Fg_y`}0>5j!Y7%0qbrkteD| z1dGDf_I%s(g$FM{`d6l!i~ep8fL8{fE`!?f2Zo79uZCITDSAO!f<$d)!xBh+ZtCyV1w-}Hxa zMkgF;*({C9h@^6>1y01eWhalnAAW)AmH8 zZ}eKgRC_Chd}ribFC~3%`C8!mVJ2AWVF4oLy|uIg^;qkYG+pcJzrULrdvbXcHd7k4 zs_4pTx%aq5z1-1@(g0vfUJBlB3WnVi$z~*;cvCW@Fgy~72urp{%Lz-}2yd<2?@LM@ z5d{2Kdh9kaJ6@hoL3kxfmT7tpZ`;?An}1`J%}a>*%mv$Q|AC!*bKp2~G(Q5A!ezHR z&A{(_z40~Ap4|bp1pFo=$QEL1zmHk+yqWFadf?{djC7fV?J0(}T?EHN31dZNDP~NC zQW=PF71eyZ++~49iFPn~>aD<=eT;!R#(7#il{a8-J{wdn&Z^KmoD1ykI?7l|P zkKL&P8?)3ofpR7Q#Q3rjpS-zdOPpb!v_CnDBZOy#s3{ulOD-~gjHM%BUeE8NZIsxE zh(#DECc!twitFDVvkd5eEbe3D%$AE|S!I$&vR%H#8&_o?u5TINc+*S z+%;2B#$T9%DmA?`n?rxLM*?qVW|gvb=dpz-)Se^SAR*;n>YiodpXDOGm+p67`VkCd zKM7|Z3rQ9XWyM<_CiG%LCPa@qps#l!?gB@3c)gb5fW+TzO`7BjkH=z`3_IM!%r@|ms@-idbpfmvs zE-uD(?QfBi#~+prw2(1+Woy$j@6)R@`kr@WuXsg;t{oh3J6td0)|eP69lBdRAFuzV z<7*-Foc39acay5<<9qy5XYGg0R0C0e2k$Y3zB!e>L>fXF0uOo6!O0; zjx?T+>QC(kGabCF(U93gq%UY{V7g|f4YDjJ+0?gUp=R{WMW z%cPbl@SVo`svmbA1|n)!jY6yUmnshCmy&c$sJ(gf3N&ugscTlji9Mpcns{}axuS$W z#tzGVV$}?VqBt#Httl-i{Z%U0FNi~t{iui>ftG}&IrThex;_@UGz*U`7Ke?BZ-BhidCPok&xd#XS($@1G{H@mUnzsW;?nsSz z<-tKf!00ymp=#1JHC}n$kf6b>Oq>l#5u#fn8=X z$m}#wbifQhmwRAaBS%zm)$j_Nt;PMGXU1G@DDfzh$$o$IyNXf9uRL%xttB%R>k3KF z@+Uz-D}{2qxXRG>Z|}_;_x{UWu8poAR#(>CuAi14x)9=g$@8oy=$DcUD>oinBeB(V z=MMv8ye^OskYA=A#zIvC&T0(5*`F{9%@bEjq7))`B|%~OWk0vA?%0SMMV0^Cv1R4# zyOjpD^z~oY+l>8K3>;6QGz&1Ds|=hlHZmf1$oo~i9sKm*Ez`vR_f#8|6q5lc!C(aG z{|OaKJ9g%_`N2eAA*^ioXA)pt4Sjn-J+L2>7RaIg+HM;?S8Y_##j3@SDuDOMiUSMd zFtyrqT3s?*87bDD#pja^v;d2UV9REO729viUBSCRBM@a|yQ=w+So@2b1{OXoN7E8x zTs`jBf_uN;;8Mlsl$KElm6M~Oc(7a2W6-D;4(%|E{OuJkxtkBqQLYBj0$T_$1PFUo z6IP_+^%zL{*ewxd5ePuH zHb@IRnvUSk>L*Osozw_ni30IkMv^;iN$N-l!BH0 z&Y#{~Qf6$3j=LVP{>L{mXasd(`LRgc+T7}EXuvkJ!L3W!uLw&+rDXH(iu1$>@!8=R zD;5U@SEO-dAD~qo+t$$(so=v#aDe34|1|c~sW-{IiBR-83c$C)<+x5VZWG`g?|EVA zacjMnXcaH2=zB3}mh=4(8d#p_x@s905lp(K@gT zB=3&lf9X?XC|~a)c!vSi)6v8D<6~*&1}a&tn9M?WpSGe$+OBo2o)4kha@ckg7CoWn1vIp&{NMSESFy>x%Zc%`~GX46`|iu z)b^m3%z`K*4qw(--UJ7>pQW_p!(ZxwS0={Vzr6iC`NsVSB>;mjw_iER+1AnXc_i=k z)DA#?f17jvQ-}&lyDqI;%Vhsk=gi*!(u3iaY$S(EtLQZ1EQy=b)L*elda<*x4SPa1 zT(xCFY%`O$hWjP|R@#p_Zr3V^7IvJDZoIW*+iAkd-QrFH9O5%SaRO;T2f5#On-H}e z0(~XctFV1$P%uO3L*aMuKP-MkEE|xRu4htGzZUs6@o5x>tBWGc*3Z-cnv=nOuiTUVKw$Wz3i}nWA%S|sw~o~#O=w+DzFaE zBoNC5<38wU=9op6F1_Gts+UDaha479u-OxY7&g9u0H5wfxiU!QZ;4b=$S;NvM zT^^#o>v9q*ViAH5>Mz{}^<`{xS=`vtnGIkFi}&UnFnjP=I-*Y$mj9w|RYNj8dPmFs6)k```Tp{Lck7 z;eg(N8W?Pk3QPv^?sHVPatR^vOW6H}yi4x|Y71QTrF&v7SJX#)GHq|k&JI;jD%*X8 z?LMd`@gB;Td-E`g`6>W1v0R<#GaS@96+&3z6hyKwM7If@;*A{5!F1}NfkR-k5-X#d zEvF8m=8L?u@q2SCuml;VknlY}P$xP{amFK+Am16KtIxIcNPBpy_v1+WcB)SSxJg6o zDrHB7zw3lS*514f{~+YzoS?3nH`jcO@O#JX4|%Ye!lWcRE>OrSR88<#chKCKrE(0r2I3XRL~#{nlXZ^pv$NWRmj89$r_=%-0}aaYb^c&H~S-K7+ivaj`|g(flhjcy-*}? z%vri{(^a%>w~gz}--CeWV9QM7d-0^N|G~-2_v@wKm+u|+KK=KVYUl)=TyzIZ#;jj# zEJ7buRj!`^a+#0LGPPlx`bF?D*EOfw{dCWj(^kpjS8W8KvmgWp`V%;KJQY9y$oBNJV!FWKzSU(9OLDPpE2_t z!ZmR-3BhgwEOANzS|IUzm389ET#E{W@Dz$lpEtKOk#c34}f- zLda+fk64i}W`Tl?Y}ls6z}{YonXeLFif1FG@NaoI$#pPuF_67?$EO1@*l<?=Lm3A!?OiM=)xnS`(}N~_3FiAn*YI?{JY-nQ_P$|P;L(->kC6SGdkY&OB46qzySXHTx**w=+D&a+=gHXW&)wA$90?SES z5;)A~sBGxWs~IYoy%?t!Z45tC{_boCeE)u2URI@@TY8{c9Y5f4Ke529z$1bFDBbsc z?I)Qlz%8>T`RWO7Rr|IPrKmCV;dnx~5&`MjD5C6iFP#0aG}RwA1T| z;Y(BY>WUv!WIbOpG25SVI<5gV^&Im}dO!DrSp?E9RdMXe*hWt{#cMuQ4NC}o;$-v61uP|63W>Mj&No8MfsA2PV1 zcmeg*4(;{p_3QO#8Ygw9|8^mriM=Ua^RO49p#9FbJ5=r@QA_QD@eJe6f0nE`)Yu?2 zGAT*Nr6RG5lvTCSumGWpSljHwUyki+9iJ&*4VV}C-u!xQO}gdQbM2V>sqq*~Q7|&f zGpWMh-8{1LJJ>tABBE9S>ldI=WWrCzKCv4{Zzd%?(s9<$NjFXtmlWE;ZtoK6MVg`Q z6i~~FRe_b7#nb^@n6`bv8ApTy{^%F#*|Lxp8EOCZg^HaVq0blwRXkC0p zIk9@^EI8O$!qwZkBV2nhWybLZx+b>Tn^T`#dfu#T3|N;sCXdU7lc|;Z>Yd#I@KAxc z#VuEwk62&P9J1H24WCkCE&poQ+SsgFlR`CFC01Hj{;exF1IQ90T16So9nU}euCObD zfQ|`u`o7tGBS<)4#?IhiuJxch3_Oc`mP?u^R4ShG$@{j#saKS!br(HgWISEHz@?={ z@huaRvv&F96pQG^hHizv<$)z~61hwH0&o!Ntm{)1x8*!iI|FXl8bEGVJj(gUm|Vi@ zVym`2Z+#@jiZHQ2_>Xv?3_34R2oSL#g8`ez#dKBg(8EB$%#m4ub;5^)&+qfrm!xMg zu|U)D~U?GDo{`)=lMFrZ@zx6NMK-Fm}jS4NNIB4;MAQNK3GT_ZfUg$r>kyh84Y$i4O=FSf9N}Z))M_E z%~%FFx|uLlAWyw)TKBnj7EoolEfzTQ&BA5zd?%nPheoVL(E*wM zx%MM8TC1v`&ie~47}oxaZH=oeI%=3pvam3`4s7NUO?ID|CSFl}-}4;i2Akd30hJz? zM`x`3&9ioyY3U%??Yux1P}@dxcPVRBLsl*l6k2^(g9kd!laHFfW%d|R4&$;6xr#0h zWuB*_MXG^odmGrOVD2VP$aw56{XpP>FZG7DcThKaL zvkF-g@WXR7*DT$YU=XkvFpTgib*3#VEy{kYPr?0yBdAzo0e1-L~+N;XTeZ#`(p;wsGEj_8dq`$qaP9M@gi;w@6IQKXL$OagZb1ab4Jha znM}vfX2~8vFT7CagEH!%d%}Y!I9e z25W5PZtRdSH#&eZi?w?P!p))M3sSwv8L&4%d-2rjIWD=9l#+t0JMJTe-bbCd5{>b< zD64F6p+xucxn~A`%W%>m9mY!vZ%WRok(Z5D7n(wFbF}Ghb>h?lT zexRWz$-+cFt`pgg4qE`IM9%4+{4<85$H&Pv&1l}u>kJjCfh*L_QBV#CeV6NA7u8yv zu%{KI?>=g+Yx5y;P@(Osu{$K@!YY$NYWczn1WRzePE)!NaM`=5-riq&cXmn@pC!Ry zV;WR@G{*wxoe&Xiebsn-|FkkD+zLPK9C&zaS`u@5O5m(^Q%d3XOnF#WcpR5Mn1Y{q z^|%kTZpFRREk9J)XNhshXO72O5jSqJ%R`UF3N!B=t(-Mo-n*lTLx@a+pdLFrF2ghI zZ7&3uUHBpf^5vpe@Oj(+j>FeOxyPFq)=r_&iS`?KdSKD#%ax+1ib|9HllDWN>%Ug< zC(GOzjB)p>O2C)C+suo$1WO? zhT>IR>Mz2Y4Kra<+AY)!8h3Z?y7;=TZVFNep~hX9)UhOr@fH{!Srzx8oXnCy6NGd( z5Hu_b9%`7Hve(oPlVytQnMlkeeKJ{GUbZsb5n+jpg7g0SA8o#6N!5rwP1qnYaF_CgVB8c$-Jz2Au_u^QdQNfXeCJvJ(;E zp`ELQ)Hqxtwjmq$;mj@`tE*xklJy9v#V_$R%>^2DTOUJvKw-;8ICFu*$y2DZ?qSLB zJ7JF1KBZ)wpyalm9wrP60%W#xNXOB2e?~RjH|ZT)i-twrcR+4N;bUQuKrngY0#;kX z%~|xJ;Gvxa(O)OUI2E)JB&f)uSPFb9GdWJ7|&iTU9^-XyV z>pp(x9ct9hzZ$z&pbpx>Pgs^@Sdxg01&?jo4f{0iKPqIq6G^@TJ4$u0(i*%_awcg1 zpn<>5rLJmg#az|YRAoPV0XfPiLWPKLSz|)G;%_Uh>L- z_Tz)6<#y20Q+aXbUsciD4?7=2&;wGY?oX(PrzB5=czrO|AB>!ke2kxGc*NGmxqn@> z;DcdK9$FLCddj5_j>%JE*q%7fm6Yp+EUr%#pfQFr=FXy__~1L6b#>+s8B4*}63#9> zngr{4VH_sM2Vy(r4lMXLO}K0Ypd#qdZ;js(Ew|Ch3*y=)Iwur71{Th5qum`xu)?O< zydp&gN~rbAj+5alEHR$tI@m2$of`P0zuc~Wk050sfVlZZ@n2o2u<*B5eICg=uL1yh zd*gvi$Nb_0Dzv4wW9hgAVP)M3D~TQPUY@J|^55Z$9TLrR9Rk%FQD*G*&LJ^5)FSj- z=V`VK7oKV!kDZXN=z*p4(~;7B#?|UgIv%<>s(7mSR3dlr%d@>gk+rWlmt%VqR1;Ja zH~xR1+3`7MO;3Bx5b`8V0IRUg{aEN1yNJT4q0^c_lAZKhR$-p36Y(k8&^g#45vEIZ z>s4DKs1SZ{#&;@lec@P5`S&3tr~T)RII7pG3|D9(%kR(7&{)gr-h^6J+aEf}&EE3S zwGIBIxP>$BUXK5n@ABn78a|Z30%y(k^C*vV^%dB>X@ZL}6x|*p_NP~@Qy^vzd6w7z ze%CK+sYx8WJp6V}HeO+*?q28e7mHd-#H1oS`&HlikThMgo2^d%#g7tYv$@!hn(FgW>-6C^` zAK8JVI;FWpOSxq7h1jn_cSRLtmE`*qZ-6I0cC-j)4P+g|B)btpSS=SDZc)C)*~iHt z7e~&Oi820Ztys|`(rWRVl*s*0)H@<;(CaOcmo838uL@tyhYj;DY$8tpJ26-oy>;NP z>T(#~SU3lZl4UDMGd^BUN=`eVmrV-mgN}p!7nEfTt;?B2*`nt7{8vvKq){-e0BzM!wehzo4KfC%) zY-A_R6#U6-@e!-R+BG(vEPR)>&Unh@77LQ0C$vQ5Gl>;)2$lv%bdc!#Oge)QpCrt~ z5GAleEFosM^Mp>d-xE)<=xr3hE_r!jI9n{J0NXAX{9gB=5mMTn!MQN} zW@%<#?m#QC1)xM$y-$r8!+IDpk(MHU@o_nS!e?7(9r}%|(KhH<+xNcKtnTXJ*p;aD z5b9nKxK-Kg+}?=CPkDF)vx+0K+gS!2I*oneY9G|g!GJ{iYRF`Vtob~QIhOx=Z`xJV zos>kNIbJ!_Vv-aE1_a&Te5&)6PitSDotbH?i{j8@Ep&?`Lu@N0_mk8JsqOtDV9TO8 z(EHSC`WH(#vE>#&#lb~=95)K1$6%e$vKOa&gF_gd)$Dx2#>wlWlssoANq0cOT`Aad zNIn+%Q{u%)@AGgJV7$ZHnQs8=YP0dd|me4(u`srol_Bj zP-~NrbpH~#QM=ZHETX+Wc~4Pjr#ks&K{&Ho`k}*bh}J~mcf<)=_CBaCSTd&t=p31f9!TuaqUGWZiRVZ?xGH z3QEv^E^>dNa77gjzSzY9n6U!xe-kcAqI$QmVAG15^hDM)xghc5^5Qnms`g=%iwj5i z%6?{b&hfa&@mu!DU3fv9Xp=8?yist;D{0kPeEQ486j*P^^Rd`y{ zPr4O&(&3wM*8YlGx+|7m0(lI70%l086s|qF`X0SefG?f4Oq-l{K$o7YMDKlj?zhJD zy$L1{yzdSK7-`@nCne$1$GVaFq;1Q`zu=@<&(rjwXt62v*Q>5diak)AMHpMUVJ7X0 zg=7`y1i#OfX*4aQMY)WI7J)+OVgCCZiYw$J$#~{B$l5FhE9jhTmKT4eka<9mz0&JNq@E@=+$7s|M6MwmGimN^}`|;X79H=>f zM)2BdK!6Gc_7KmgLZ=|xm<)A^*`tJui`nZ?#5VZY;1!jwhAEFNRY*0adgb$9G!g-c z2czSp%A7(7ytl7d@h}^seu2g{XbeBoI0>4}cG2>h9ZYpC`&Jvhg}QKTu^BiGdsw z%9&9S5~2U0eiC!m<;T@l`zwVwx2J$9;bmJX&l=P%!;@Dv`YcIrBp*H|IHXE1()Lw+ zl6H#6+9RZ5&}bf@At;~7EAvA+F#6nDr@9t|SvAFkX_gWQ>o(JgNCx@j=GwPLOqRry zzEtM6h)uHDu}eFL%Lx6U7KfNMddF5hKeX5KxL#v?cRGt@x@2^?GWdpc1@78)U})4n zoE1)jR(Z-CIcYY{_5KkHZekGng&fnNy9wG6P7EJ!rIl} z2vB0uIiCFir%&j)#9u}a#617@|CzrRIG3C$Ad%n%)`}0f!oizs-E%z4AEKdwhmBdH z^w9PTA9$_LL<2mJgo7zcze1^Dp{6bf0 zQp3Az^t6KaeGxgL`1%IY&b{SYzR8*0>i!D$YCe`q6zP=Xnc>mVaZZP@nL0W zBn56g^4Y>ss4A328r&^0lQ|)IomlFlaa(v<%BDlW0;Y;4ajWdscEH3qKF5#p%6_Ry zj8}u3*ifBBS1nDy1dK_o2Ux%QB~LgRf8{5?Gn?C2M+ebU)HGLDDCD-iDxWzvvyfVv z<@{Lb9a@R#W`b3dMWM=!mR^@TR!w6Jyj>uunMX3G_PA>h8G4Quzd-%MZavD;J#~Qh z5>n&fNvp}2TTOIAcqcFrFfGK(@{KZVMHQGWiHa5rDDLRI;^sg;EDiAyY2LIHAgR!( zQTwHc-tEchfdDg^L_|R_E^AGqgr zUL%yyHAY1YLq81JSv97U@efE8%&GrT{u>eM>~zXAY79s^Rx<|J_c1dUkwCVmB9@1d zJEaql-dRi5n%FWDz_SHG#>ze%#73?i^R6`al}u9BqM6JORW86H8>2>ez@ZCcr&-CQ zRB;aHL+AmBQ<7T~UYr_bQzDQJr?cDm>Fzyl}(7>U=` zX;FyoJI(R9NdCBJqMsI{h5zXw1jT<~RQ0ts6+?O+gnyUdKFNkNdRStxh{gFCz|lHn zLG`=DuQVcBF+(A*pVD9DnTK~fOKDu~R~ILjH+-EF1J@puCN~7vwH-e5wT9au&jk2G z6MUH?_LDSsl)1wVlB>WR7^-rt0y${s4n?zlNqYsDKAd%_)vm9$=>+Oyz(WQWBa>P_ zESqkWA4i{;uEFP$l5WHnz+mR&urUYQ0G>nE8wqLMDb#Q{#r3Q}*UqqY_2Y<{anh)i zBzD|Q&zVPX>Y=GWDyI&_`;*+OFaz!u$=*HW%;?{AP9(DO=fKe*L14yGNCBK*()66t zBgXOd93arN`3(@8$2P9wcG zcSOOR&d}xBcbc(e{fHY~dFLP*JrI2@;M;pWpIUu}-n+UHr`W3&f%e@x?(OlOJy;EN zKvO{rYIFO%mH)*W@g9=xSHn`v++Fb587ORlH9JUCsGPD0>!aS5Ri48w80@xtXu=K) z6zCLL_3iYmWfu;te^6-cl2kmCp))i!-6ecVY2bJ$@OtnGbj5BrlX&=S2yA~fo+1i) z#|abmg&ZMV?~Y?jTP+p(SjUCWE;PR(;;0#9fI;Vas!xbu(?S~{#DDDnSO5;bUv(be zGeq2@X8f#{Q)}U=9lX+Yay3m&Hmybtej&3cFd$!f$4XdHh*2*1!Qp!OLT&MizT(ah zf%O^V7pDD}ZiRLK*Z2(LeB}D1qxQ46NHDsF&SvkEmZXiM710-o8Ee;dj@-i9+Hr@; zuZSXP6|pgih4WAobeARjb5T6LB9kaFn0Y;;c8Q+yyHTMw8fkNdT2Q96WOd!M12bs- z07n0b%l#x_ElpTTrXvjbJWe(UnC(bTgm6PrAb*d07h%f3IMNC2l&_ZlH4yK^#Snxn zVPMY(#$tH?m)0ha}&Xge01ZC*rWeh{Qg>$SO*Y{Q$UNd)Z9d}G9;D3yYE6r z*2N?q&ZDt{j%^vVt}K8(0TQQ6?|E)SEVDA=L~BVusA})Ql#qK%EafY|#_RfOa&tJP zG{37KjPD{@v_KdkMtaR{6u|W+tXa%tx&{LojF8$ed0Z|)rY;EGGKsPeZ+6Y;Q+5A< zYy6U!s((~5M5XIHLh8;#66vg5`p&msCdyiKLe$_{cRuJ2pZRIR1)>^dyklh13WOlU z=T_;JhsBIrzXZ%!V#O4n)Nw;{Ro@DF=%DowBnTWv8!2=9Dp)hB(%e4|@Qb~gG-KCt zkxkgXVh4W}DFmuU3}KCN8z6biV2~WOljF{ZO4s3h{|XAi3ZHp1XaW4z*KnDm{DQA| za*ex*4c12jamU=-5#P3dhtERNg8v0er2ZqOzH8K8FLJTshe1oXF>JV{t6x(}M%P;j z&Xp+q(c*}b;=6E}L&YC%1*aXZl!$#cifzdxwv$nn=OSt75O}2&`Z& zd~`c@?G~R@fJB%k{hPzXGurt1<_oJB+ZbE3 z&b9uas9UlN_Vb7ve-21Cl74M(6Rk9Go$?G^b8Sv!dbz&_;YVKH)&vJh^xN(Y5s@XE ziJyODKk#Wj`!`}{Tx{rXwNgwZ=~ch=N?$q<>=r-^1_W(>5@@mua&J#i6BU%5TJqhx z$i*OWuLWTmfa}KxD>zgV!!$}LF)^`C zqoBX-Q-ZH=SXmkPNS=Bfqh}81QM1`=XP6voM%^Ez8d7MCKXFE*G?iisk+g0+?85ZN zap2?sK?&lDd9H-)S2E?>mnmb1f|E*K#0)o-l=RMY5fIdUZY(&1np!XM;IH`ri*)LW zgupiEZSJevMt(O0|HH<6b~T{@?b;~>P^73dsk#+G=^{lsx)G)K-UI;!LWj^3Kt;Mr z?+DUM=p8~w=}IRAkQN{iN(e0^oVA~4op-$-&YJ%)Yi6$No{^#9QR%rxZD)IcZDP^@ zf~BGB4vzk%W`4<0QcG8-S19K4u zE^Nf7&%m*#J67(emgeSmQh%17WGoC!>7O9JQr22dH^)3hI}hr+;dOJ`OY$H9qwP{& z5W@IQ%V0jZ{8#xEV7;hz;JFDvNDT`5w?Ks7J;48G)k5viz2P?%o`O=XN8_yKLLDqm zAKQ|38JihsH5F_(xcnw6hYTXRma1ke@@hW3glMAUtoUQNzO_I9W%hZsBk*%Yt%g>5 zi|hQY@^nsH9~%^Ew@Ix*Zlh#-hb~v+bvP&B0srPmCeE#yKtC&lx3)HR2-!4RUvlG| zqdgf?26{`b+OP|3Vrk~xDc6pkhyAjZWn^!mUvbG4eOQHU6*>F`5fB&tmNJe zCbw@psf&PzlWK#!uq0B3GnENrnSN;+1b-x0<)@=iDt~i=&$HUet+(@z#yf?ki~TDR%^ zJ}ni;@8nunJ@ZTtI?a~Gq+Ofbl_@uwX&w*7)1FSPF*c`K2M<_iXb=^Bhj>E6)Qqhk zyO&mKYTiNOZp9F8^%tlFC{wTXDdXQhvKIK8&Is-73bnTCk|cd(-J3BsXv7uM4nu*5 zV&i~dJ%@s))H0F%w~p^LF3@du;IIu-q~9}erKnu^DmHiT{9IwvWCWRJ;~9#_jjN%_ zB%^i4LxSpMaD(dQ3fLF^Aby!~_iQf@puOzMAU(R~eznQEcAyv4OFqTi|EQfQXHN9l zhOOA^&S5Sh(YM&^-z)lj5Zj*ByY-2q%i^0_ov;16)bz<^j&qRPuTU%E`UM&sbkdDo;BgU#`7%=G;8`VlR0vb@TJhWGM4ns?)M zR0Yla6+^?}j!V_v6Ok;~=7@XS;o1OtG~dH|mtp^kwCrF;cE=15zNIhws_}S!;8YAw zLn&3LMN9#Z?MKf17Q4r1m%oxt-jV)>7Yr_Vjz1&0!bWP;aF=VYS5F_{$o>qoqr^{Y zI(sNWJlddfc+MNXA;{nME0I5Q^uFi*wyf0bvh?MVY||`HP;18trB4bA!QLCoJstKyNvKy2bJyOAvGdGy77`4kb0lnl0>!=@s#LL4>^ zK$!}q@sU&PIhU4J0@lbqU#}wM;1rK1Ug)nqtarB<*jL*i|6`4fCj}q>d;y2iv5NSp z02e1^7H%Rr&z>@+U_UW(76y2PqkVhcPR~^)J#Xy0%kj9$ygRP2%ppoYaiO%ba~C zOa5(hH^UgW+l+N#RDtUZ_YH8ieJ ziWu=8_Wu2Q{Zz@}>1(V8yzG4IJs;^73AMM}SuRf{6M!}X{vDN)wrsT22M-lZUu1e2 zkazcLN{Nq4oL24>wl>}zp>KeP`1zMZ%XwX&tr3{My!`3?lHS81mzCY^8%qno<2nf0 zbKU&$%7v7QtyywY#UYdFkU=?3EO))v4b^%wK%bt9hL&q7%4oc`UQ^lovtZJ#6e%I| zdR<>Dg_2#Ir_POdd5`c5b>|k>s1)3X+QTo2dB$oaGA@ zRnOr5?7O@rLBNtCk!h!rhi1xbB~^~!}Syum+#<;OtdiRp;Pi#-rJOHZ>x7pQsVa>Sxu za?FlORj@1k;PN6k0u zChL<`bIso7pEari*1no}(#bV*T>Cm-3>N~6IMj8@M$P9?s8TYu+U-6#r!Ds>2?U=n zs&R(*C~|QE+?}0{Y>qz5joui~o_C zmLdc4+P$is0q$-P7uZnmS#T_RELmD$@lW+BV=0St9Z%@QXu8B;_F+R^tJSX>;`NoP z!JAC)R;$`t=|nD!`Bm3a;@Z5&6o<3D$7V6n862<<#8M^vmCdXU@_%5>8+<1TZxT00 zCtD%bdbYZMJuinZP3mQe>*+$s)bizK(G*2Mcw7;u*>puAr4xOfHYAWX-b5V?dcVE= z!oJDf%i8wnIi_B2_u#&i+5GXK+`flFvG)8AtJIP9xjZrHU#-y^MP9eqM;a6^=Irs^ zG(0;Vl%-gUg{z2Rkp^!}C^nnBDxn!#Mb=R||DXb|=pC2YdrHc_V^g&@SCAmpd{#<6 z*>`j>nI&tsxt(ngSvg&QwVCi7XYphD&->OAU{226%IVBdtNv$}%NW@5S|?!--e5jG zYYhu|tP`|T%yb1+xJq@(+QpNG6KP7m;mc5bFgACX``~~|} z?!u{o-&!&yV4GLelvtnJ2U|@`J4X1_ZH#d|Fls_`55oEdhZ}<6v%heb2 z=9xSm<^C51R2L7A1pw2`tQyRb)NWL7XI`bJCuU=>8>+FsT7_mPbk*2Dlg5GT@AEW6rJjC*#ygAyB&$36}3x_iYXD8j?5BV8fXj zU+tZP{O6-RBI#1s@xVdNzn@ob(+V>Q_2FwBGBfYXZB>MGr53gppVvl=-J~5$Wbsi^ z?G!8%N@4NooTe4YG}#+q(-fEVi*U^t9v0N>Ft@-Z&k8VT467@Ad4B$AYcL$3EH?Y; zPfc~T?)5{Xq8%PZ*R;~dqwywt!bpK8oElWSW9r#{#~$)`UNg;h-~G8b!UJ23>vv*i zCv6$_yMC2)3F`sJZZ8p3<};>ag9a&Yd?lt%$Etq4@z#(F0*K-r-_X`~+rQ^f&Wsvu zh~ohvT|I?M5V-1aY7oEQM0gkO?d^6RBYvhi!+9Wx)OdbH$eR~=g&L9^D7mJ|{r18W zzc^o}gWKzD+VIvhAwaNK7oG+fyg_l1*T8^sEqlbF&s9b7;*0SanQb2yC)VCV7UH9Y z%**=_L?UEB+1Q}|8*&ITg_^4216xoH>5;q?U1RjtK~TK~YX8{qCT2**fJ@bY7zwCK zNB85M5s$dzoRr#i3f;KeFgL%E82R{Tfll*P$E8!F?bo&ZHPNRmo|%9$=4FoCpNTO( zTtNbzl{;|2<5U{U4Rb^LcBv@RmGq48<2|R_<8Qy{eNM7#|oIGNk3nB z&??L6nnh01LWdsq9Skg}p8TP+GhlBhx%RxuZ(2XlKq9@hBcSMI3bAhU6>H-$u!Hy`svnN?*N3bXW9$PuK0S+2Wr}7Q3WRI3 zvgSqeR_$s5ul6O^T+g4u%TpE*x!%X zHXHKA%ZRMM7l`LJY=F?!DE_^N4lu0R*Na~vC!PjH_}_oex@w+GmywUVa}N)=lfsz804CKd^-zj_jAx*P`*87uyyQ zy%u6uIV57;loMMCWzH2=kaxKsc41Mibl9xvNeN#K9&5q+&MR)hkC2AyoDoxZ1{t4e zRk(Mav%-ku5Y;vrIHHc4U#??`4O`6mB%xOksY+$lciK+q+^%ZfDaKga&;*@mlfW(e zou^C3{`lS#r!hvWjnm54JOu#!4zXHk$Z7!3Vq&>nb$;%f8SBnknD+_)=*meQLV*ZZ z@?aloWo&+8 z;JhbbBwTG_+YpN5+*zzG)G+LAkP6FaH#yI!1DF|9W@y!@r2|-${|yPr-T^9QyMn(R zM89B6{#v8@7P)tiqzkDAs27|;nYZS!5e@%>GbpDr{S zGGk|xp5!#Hz2W}k$*yY}gM&Miu`T6s(byePT}SIb$_lFnnAAlW+cZ2H*V5AwDTkMy zYV@I#)?967Cn~b?cp4W?r&0@5A&y_^0aBlZKFg~3hK)bNy5J9b85-oz2pG8UtaVUC zW|PO)d3}2tdVf{mV!mI}R&(g@Pdi3*Pfj%+hCOegorrIUW!zxF-j_0-oKyCQw-7NB zC77wWDK$tAa|f-f;1LQiUjrB?&W*BmAHSe9;`QuYwMy07!7Vgu;45=adX4_m_MSVL z&ca`A&PiqZHB_3~_X{;9$BblZwT=ZtT_jU|$@S=@optZk&7QNh<&PN!dg_TM%CPwH z6RjOEYw%oF$+M}v+D7o@kvts_ySGuq&|(Ojlu0zY46Y+A^Uh`LFH=H9H`Ta!J%jrW zZ|@@qNnlFv^2u2+$Dj$9jc0KGVFMo_2H;@`*r)x&W8xEhVB*t$*+VFLu&Zu%jz_!y z2j9ygKw=W^7v?~&BR+x4=6f=vj`^~5$)MYX_OSC9eV;#WiMKfC@N3J-t6~C(ngGSK zFXOJpdWWsd{M4lq%%xqDJ2#vji^?_K=5s9iCw(@`8}S=s#deUkFp}N0CabGemvOb4 zp6c4*bz%9aNVI(=*dVyrh0mQs>F)V^8wKCQJw&9b$<<1v(vFnP)^gs1oF`fb@-1JN z(946ounIZil);EKXStnW^SWEnb6;=5LStV#uJ`3Zx>GLkK+g9zd@?x**>S`;95;5I z098|vL*64Cl5+OHp%s{Ra-rFw?Sr_-)oAZF30zwOdJGFL> zt6Z+!e9-xTrG-N@`Z5k3a{Cr033d!;}WWeLFK|~T35=LLkx6{BZLu4O` zn7Sdx<(lAK_<60J=v)3nou>f$BTX{K2HB_zX|tQRGvLh3&|zfskZ{V%D>{B`>JG!9 z-g?*FLkQokFqz7yO5Tt-m|OAZVD&aczU-G}f4600pR0R6?Y_Oy9!q;!GM$Gyf=}G` zHyifvGrOM+fy!HGs3X`xq*Nv9{nmmh^Uw^*-!yHO&x+5dxmiJPGWXm7-QCxkkVW`GV zScY9PFo`sV$|+XO3bN3~9JQerwWP^Q)33tXmIiWZE(+HlF@QMST0p<*Aw~*}Ug3lZ z?78Ee<#B+}o@uQm9>fW;os}MP?0o&K@-PpJ@;M8|*OBn}myAfiRLW%nzEs-y0zxYV z(*GdelG~rP`dtt!>EHv(i(-@fqDRa4%CNJK`s35QxlP%I;hk&zq{QVpr^HFb#!RE1 z!J7AzO*Y2#nu(&K=Dd~$HA2d?_esn6pJmpsD4+}Au_>GzyYY)VSDT!CxKS}Iyo#fIGK3|t=Q7#_YwK3d zT%G@B#Kb1*NcP)e2d(t$^;2=xZeUpd~!Z)S$Bb&|99)wKfKtd=#q#f9?RTQ^d8 zPWh$e<7F?{+w^)U-BO&&bLex(T@L0sg*e{3cbIMvo%|2DQl_k<;xbyw)y5Ci-o);7 z+vs4`2Fcqt%!AvZTTW%}ZpPn(F^iOYcnNKadcL6}E(bjuaA{d4+Z41{6It3HVA~dg zhBlRoy5o*6rzG);W8CApVxWcs;@U=XwUCv#OS=k~F~EKFj2MTh zJv)8cxr)oog)6Eb1|0vT(Z9apMl-OtiFhhP> zAai+RIHh?*Fy(dfOd2SYT9OD>j%W;o6e?#T{%y;9QF3#b|CKGbUx{evSp~1zODDan z3pn_nb_E|$1az~9qe*|lqZDv(-QYN$OWeFczf^8_uXvv8U4utA7nq0JKZYA^v310Y zhLpH+E?mjlRUCZ$IlD>peM^5*2Ib)@kT+_t?r6k)W0BC63VXTjLO@K5h?z05R76J5 zOJG5p9C8}(B*m!x`-6WHy8ISs+f`)L;pzGFW5u}N*MP~uw_tYqf6I9hg?&!}?p0xA zgyY}EB1-bDIa^O96}{{xlr0uv+5ON=1K~*_Av+^=Qp7=7M7Hk5c%r- zo~|SE=`t=w)aKic8u&DtQ{l7o!p?JoB?$YAW^6bdtdvN)a-a1>yyxli?Go*lJl1X> zxvo$Sz8wF(`k9_Q(^e}wq-eU0PwvuMx^B+YtZFWWlj zf7eKUPjKnSnxK<1>nT)Gt5GiaZE1fD|`!o}CzZ2UlM?&b_p)Kjp5eWgli$>Hw&xLzp3E3$>tujl7T z&v1zBTDok%V^9@J4=d%8<^KhzAN^i&5c_z%QYtV%MY_41ecs#rt!;Ih{ksZJb;kNx zi>y0zj#T6SejAa#v>Qv8f0Na=rUU!2`Q2x5VE>AH&~noTtw;&Hxa6`)IAvq_IkW&+O^nSzOtF54ydNAk6 z3mXx~Q=4gADL2k_q}$-Ha2;jRCdH=NBf>RW3)ul7_4_`h?%N3m!MfVoDcrs~BzL@T z*Rz?aY&6E`>W!R&|4-X_J>CpwH3Y>*+Z83vh8k(#j=8+6laSOvI6GW3vJd!58o#=P z<7))2Z+R2{h3d!{oDSQ62ew`uQ+{Wj z3lBJ<6?uOE54O=yQKwHSfq@uAzBxjH(p=NlTw~AQ{JVCi(ojKP=mU^v%2}0+7UC0? z8Zl+f>@hruh6h!D6L1Aq3aF26vMLt`)(c>wqv=7S7M+H^RyMT@%{TTWgQmQ+F-YPk1=To+VhcbqM-%($ld!J$b z735Ptb*Bs3&x@Ge07sPGciqvG6Y4T@9{pF?RhgTm(7M}t9w9R`76q+&L1@xUe{p}Dh8q`%Z|`&P#++m@kPj9Wfj@WIM0Dwcq>47gMf2FZ6xUG%N|9-l0$FXGu^m*EM2)a8Rba)Qa!0x}cSI5lrO?{q+&C`|8BZ0r?5SCSYD#=W<{?!O}0;bxTz& z&%1Kv0eQf03P^41MRmkXyZ9sY$Pc>&%DCtlE!!TRQv+(kL8)O`0_NM^JoRK7#Va$| z?{jSHo8C{&{V}Pn!^qYJ@&=O8l-EFqtxz}y;&FTBQog#x@vB;OnG`d_k69OAB2mP~ zKA#)C<6DWZ2E$;Cij;4{w4Toj@g-~HJ}i9m_<5%sU&7|Nj6rXWeU}!t})fVsFwCvkvV|jBw*XNAVBD{WXXa_S)om&_?7TxquGhaWQOiX%gF|#s^YX;-Rmd+{1?*o#?cK(gHeWep3~Hjw+&}F?f$1FqT(INcrGbsEyv$vQwj3Uy z={ZOKHqFj>FQd{(Qf$fF{boXy2y^E4Uet7j8t?WG89Ze-ndzg6hD7EXs;kVOBC!?gj~_~g

    S>Z3c=JrGLUMqW?r+}@ISr2;&bH&y$rm5k+LbSoS|04 zk%MY82Dk^FRC%RUHu_wi_*fkh*~6ew%KOY+Xs=H>r^J))+F>K;{P*5ZZNKjiwp#rF z@I3RX2TCA74NfjD#w84wc6DB3$r+5zfAUl%OpifThz!SuOa!D6eED4&vXoZnm7fLy zbP{K9ZurG{N24r|-)nFBoD93Mma?6D`0OSd?@|2}yZa-PxB0bw2f3wR6yB%Y<(#2r z%)doEd~QY+WFg3q(xuZ?AOF6wGpa|X3j+uR*EgJyuIg~tBrV?8A^CPy%9N+c?r7Scw=<7&FS~fpE+7f`rAs#)NW(@LrIM%1v#4kf#}KWNoU8=wm|#v)zW| zp!zt|i;EGvch2rn&Vy1?Qu9*A%Z9UY3KC^2&-dDV=JlmrW|p;pZYiBn;WJZPUH*i% zfxrdy3$S|t6@YP3!nb}bN*&`2z4i4=!WVyl`aF< zIW)G6c&G}ftP29Wpr$I|FpJqChJ_a^zGXBwE-`ltA7YJGU`Q&$6c=Epmi z9hP+bI}UP-4Y!)HHA|DMxf#ZL+UMUC36Ft43v~I>qPr8M{rmvD2|RdkTJjOn3)uhb zpXj98WQiZ{&5)66yAE(?;;Jmw)B`0M3P(SqX_Os{s%s-FkF9T(Xh}=TMVl;-y0Kvm z;4P2oUGNLN-alBWKYKhjx(!D(DJN2Q=1nh#9`U!kL6 zY2dJq?&v#2abh^lEAmJ)l`LlkUqU_9%BnJHXoMbs^@FYO5453_PIOX}O`Pq&n$bjt zTaK2N`u~_MnDf4u`%_NCL?K2}N-{WX6=A_MC)M=prM!+f;Ins>vK^~=UM>GiOF5>w z9e|6Qb$L6@#gp7>T|QHbVpff6u>IXAM!2#18ymy4HJ*^muQ`7nbn@J1`hV0x*k@%9 zK;-`S?`DVlu`COBmM86lgQ@)TF9G?Xhd=Mj_52a3Vze-JjnoVB>!fHYTi3#`r-YcX zPL#4-g>a(0QK5|mj-n09NXmJ`jDmz{=UjH^LTP5h*FAYKCYUhFeWIq75pJKky)P1G zRI6~Xmt^4hqoTYfwYTwP9Nvj0TTAtqMmEAPO8E^9aMq01gTC6(v5o9abXve+bxEcL z*#JzEFD0Q${sWNNy zUGB8OBz^Uge9DmaVM)Q;$PSiSwpGtlg`HVme>sQMy8C1Bo@;|Gbz`yyzTXC0RAX3i zFVCK+gf%jxW`Vl0FPv@zvJNjA8&SpQ-rj4aQ$sE1}OH=P7RePx`rfZw`7mG*@cZq)F<(ym*y zAtLPWzT7xy_5by}$=Rrqf_Z!0wn%G*-8PjskKKd*i>Mcvyi~8_V-e>mIif;wy!SuD+eI!`m@9a6Pu@*hKM^@PKCfM(kfd5OtN7Z6T!G7 z+E9jcxz=ad=<~HJZ=u9KkS8hh_EFhCIU40qt*#P&y}6@06?M~{$|?g=7*cu2_GYZF zS7_+>h1Ku(s{eG=DKkk%D;$ed&jJFt5@bBG@_2~R`p7?$#CilhDHAH;D=(Q#GNt|W zrd%r%?4!NoOTD6rZnvs&jR@Oy<~_Vd3@`0<9eND~3xKj9eD(7f>f{=rqWkSQmimp4 zH$}~QSxZA|6~;uqfST`G_#y~a#(x1Ox(^{@08^!NFah$3U`c6zA}tOVHTk}1*5aHj znCuLTv+F0;nF5RiS-bk)dJt`6euGLM6l;Klb!oGP@^`j7Yy zy=A6wWBdy)@?rIsYMd~;6CLe0j+!Ax*9@B2uebbB{}_<$XfO|$M)qf>!@Fw3-ELED zHk>%BG#gtrRpe=1i(U1Ff>t2m!n}QgFX){RGIWp6GX3bQcy@*$TQjr_BG&E7)rR&$ zW|;Xg<{PKwtQ8=hS=<V>Gp7%gv(n3F`skyYH!(? zWP&URr7zYADH*=pO{aQ)_T?UaJuv}hqj+d)k#sOMIsWV3)}ULBqQ+NI<;{N<%9mR> z&?62385Zy0)m}}i+_HWl9ZeCAA_Bs~p6C5w%s(Mxj@^Lj#(GOZs(S7ic|>zbBCu|X zNIyj8>aR2MNc9Kw|8n2daOSmtwCD1W=wQ!zA`MA_Yp zlg(K3x9}-VPFxt|Ss+?BauO;_3L2%RLvi+u_^x!E{hPUtB)?zcF1TdENVpT~gn9}PJRHEQcg~%A}z`Q zoBrAMBi`sTz|x;X^rUb9tUXmDA85Y~G>4ddX<}@=IS`+|GEj!!KRayW=%Z?WL$>7K z*u14Ooh<0mK3W=P?Ee0S>kA0o8I?I?8v4DMr2PAVjV}Zqyjs6uV54h_% zdXcH3vho%o*EhvnE^DRd8D+biNs-C20=yeqSI{i9%%5cywO+Rl+2buW@8zU2V-?QG z1!b#Ly0DHG0Z#6YCuR95P{wjf17;hF4N+ZuHYT&>Z#zP2rz$}I)`RoFuf%mf3^C~P zrJ=9)-I}wLTNv?tM&mbctY%6A5CIlk#y9<%*BI1;xaIO=Hk9qNQ6OAZH_q-qZC7IP{ho2#v zZ~D!ZJW#Kc$~*e)HLGtpqppqfrR(NO0et6fD?z`Egq+psu(^_PoFY-3Swb(3%jp89!nzrtm5{I=W&!>ZUGECFG@LgI7z% zk3yzK^U+S^bDnQ7mESI9*gl4g&^NyUSlXfY$~+;E-BD0}=95f{&Q4*5^JMv_s2UUQ z;c$OvC6f!!IF`~-3+D#qaNbfxDI}Krm}463=E6*s!g4H|)D_-^qrz9PR<9r*joc39 zxLBTz(qY(hbw3i>G&>M zB6;9rnA3Hyrtc_L@Y_d9yVGxfD@Wcp;9LZ28g?jaF;{WXzT&8eo&AQ2h8*}-dNEo! zjXA6Dt^3Di=pfRk5>JeO>nGZGSDk%lr551#+VP=#ZkZUN8^r!aR#W5&Hj8KkTfZ4; z(ROt)i)yo>97&tU)|u{2fmlY3ggz0(-+pV5O}*ab6p zt*vERFol*nHE7r~4#qir0nZbj?coZqWt$c!MyA`eYk4EOphb8!u(n)j?qZ25lk&U8 z+nP~TCSfhRVBLX#GELtkS_yp~YdNZCcc>I9BQPT!tr!ng-t4i#KXe|S_nwzOE?-p4 zJ!@{e$QYIrN}Jcd#>&X~|Cm~s?oaUF+%l1>Hs|})oc=9%_FALvujM5kk^js9@6Ewu zFoQ?a;-$suo;!S2P(SGBl^LVL*5*j|nzj;IvrU?5K+XJDKst($7|ZJ%HI^y8oXyVM zg?=9ljH_VXD`u=Asp_pwMT`FnMsV)@A3S9psV_+&U9~?W-eD4g`+O} ziEfL{HSa%GUYu?h=V(rc;NM?qF?XTwDX|Ktr5Z=#&Q6z4Q-91H#quDL|0IL_)%pi3atjH9Oh334gOid_ZLQbZb~mXRDxRFRy;OhF#UV91rRM(a*4$36 zv;6us+x&QY%kZ1jw7MSc2LS8*1Bly3fycCBm(-y|m?R^ILP_Fv1CNbg#XLl1{Vxfj zr)mrDuz)_Gsfk9ICM7SLTh5U!BI5qbSWiee&we{8#iG{#yGh&515+^4wDSQ(2Gs5# z1J(if`+Zt(1Bi|L#QxI7N(v!>1@)!MhwofV4C2h0M?iAa#=wdtjx=bq<6S$&FOPtV zJdeS56iQZG0hmV?+kM(|XajIi;zB0X5W?R44m8?j_Xi|Ix6mt8sQ6ixNyp<*<3v-x zMe0dC{y>NaAp0qTEIi}*W*7tjB(2m_7#img`po^Z5i6qOTQY)58r9O{ z8?4yY%Om+zep*ZU>Nys}q3h<(qu=THo4-2P`v#{qj00upI8W(iaQZT0Da6qX;Hg)kgk#n7< z%0ls4Eyw4&UxPZ&Tkkq|W)Pc00iG_?tT+pB=lbUo7)Yrl)O|Xxzop5kk?Xf_1^TY) z(GuA5@ZWCfX@C@z}^8RDHF47b<_}Yd>&-@L_0*m1*II(0CK_P^7@Y{ zkkup5b2ffUUGHLy0vTw%fpiSPP;*w5GugJ$@LZu!V$;u%E_$>(Hb=aCg4c~N!c;4S zq~5?!rg^DVJa60Th3PLH6<7_v(7HiIj95bFfrCd`EtLR9w)M!pm>`w-p{N_4%dK0S zZWln(f~7Zl5AKC({oCX=AI)KqUMIX`XE*|IbuZjydq4M_UHFTswS}O?wmzr*JjV;Z zjMVC4sbPP^lU6rpj!bpw(tV8}cAKIJtxdotUzK;&^L$-2OCFMeUCt zQYMT;Q1Q9$sSa{|F$=hQ|?9T^1i z*v#f44P-pf*s*v&kezcD7(1?=#5>ip2uG1+A3I2Uhgi9z^!&;Re<{=5cbj+Btkf8YZOUCc)%uLigWivB$@_W&t4$^R} z`~<4by%cjfG{Rezu;7tcj9-FMKAe0%Q@pIp#ff!ZtX={Euvt{sxI0`eMwarWrli1t zLZf;`EBtLsUQu@8D~u}_y+FxXvXSQ2Q9xZix%wfrl6a`*Ht#)q8C|lR#(8X3D2t6kN<1WJ9pa?kCeUnY*wR6^?ol$zU-0yPH}h!|0T) z#Jpeu)wL)YE<&vgd0wqUM9c`PhPfLH8cp0+R;NItB>-8Wy6yVINwU?-m3d{5clFmO z@`S}iYJ^NxgU&vjo}TE4wJen_kt~Dn-1CIb8<@1J)PCBeIn#geab4reU&XjHZic!` zzXP%7T&f)ro!AUi4TpFEnt;1^#Kfn?Bj&-(b6w9}64&Mr>2)BT|t;(1UHmzggrQR3mu8@5kO-tB@(Q5`$%{H5Y%)F0u zi^YDxQiphxQGnj=@?!{Tax#sk5O}TNImGbRDaJ1|pZ#fbN>Q>D@@Z3*baQU9!MkS~ zod6;96kCZIdbU0znkB}O@q{P~NbA3M`HrXOdW(wlp~rK>bp-lh_c+%M{iKc%)0@k8 zo#y4{Be-g}S?|PRO)ob1=|9o|f2uOPIWX>_1UcB6I~==*Y*6Fe@i6SzrKz5sL`(~H zSRi=Yi8ci9Eq1;{Mz)*!2Xzgj^yDSr8PI@R64nH$QM?%T zEyC%FXGJvmV#ru+Zu6l+L|d30t=Pl(b!q2q*Z$bOnEJFr^Ap^Qw**upv;jBUY3jXC zaHDv!Dm_RLzPxN#IC9rOEfakyg9P{aQylx%@j=unZxAJv?LWzA`!uuj>hjiq`_~Ba zAV4G@d3L^DaCrWp5WpZbo5eyCM|ua=dFNp2A->oTiH~cVV(c1rTyrEf_ix>E3=`B)4~rBt8}m{bw%d z=e=CN#3D@%DDP@;FVfvdA-kzObp4{N?D1$%Te0V)Q4neMGMl9UW(b^_nC5<%$K@a^jK(= z0u_YHV4tOY%VC(cZPxm#SVatAVqp=Jlo#h%7!6AG){mS!xgC4wM@Bzif1$o;LVaMr zz-yZTq60XF+U?(9<6mAGC}0s!6+rv)kbaSaiRdA!tU7kv8K19Boda4ye6|!Md0AO{ z1BUt_2W!cVf!u8lK;A}`Le475MRo=dGA z&u5~dId84DmgG_{Hlcf45vAq)*UQrFX8O>4MII!hL^ZbdnO^H3C+g4BLbe|8X&QX) zeLCDF7r4s|VpgTwfT+7(_k(H-_L1eI2-oIgZN`hQia_Vd1bG|5WQXrbOU5KqrMZ~N)0O@P5Oml?2qxNjTv0yl&iwP3 zk+E)3O4og0)^E(Vckl24>y*A*8M5cBK=}CC?5Ov#ef21HeqEvoRZxlcNF^h+s|SmX zE+^fTBDhN+tdvH`6TRk`X+!|Nk`ot4Gn$uaBB6d?W*;x`blB08T zE|x?eW_)xJM#Hm{k)nk4l6DqyPg+e{=g?hs#w}pv2*%eghV0}~eJhpyFO-b!(Np9R ziCPEaQOmZD_brv3y69>{5nb16%@aDA9{}UAgW&ih`sUmhSKB}z2R+DOpDYJpSe)V6 z`rXq}Z`9_%mfS#ehB=HljhYCbL=CAwvoIcVaSam6y0Z*emb_>ZKB!g|nX3shLXL_~ z9Zd&-&ZOAO33WQ1T?ZUHG7@Y@xmqTaPnG=>&EC}Nr)-(gCAp$KI^POL?0VM_Z#x3%3QxAq5V~1 zZ|yywDm$n#`SW)mB7%1 z`!K0^3;BOt0IT{ZaP!DLhNKRn(P&UiWCCI=Gw9UaS z7M2aH-Cpz91kRsgJX_<@_%F$Ux)=O=s-?lzD{zxT#(-Y=UUsf0{vOVk?!#voOT`l( z%pvhCz~1{j(HH>tjSS_P7s%5W*pk&e@L@Ak+J6!%ZSn|*1$9f=3J}dxMa*1Lqxq?_ z4WC-WYxVEGC~IELzg1@;#iWU`*nL^p110RBHkHEuJ)oRyWnKd9c*7JDqljHJlm?j0~ zNH|$m_AN*ihXt_KSy7zm`bXPf(v03RsZ{@KEs}?N=GO2#Ay;soINkf8Al1U{rVSwC zuOwV?-oijfs^-|iy>3Wri{8K-(XXrksEbruI!VPb5M3i!s=FVOBmXevv2?C@XK5-k zSERHUyE|26wDySuVLVdB_r&)Y8mD*!NGIrXW*0fdzf+#IZ?9!1^D~Js$=|hMs(i&d zQAQKX=cA|kb@(s+@XvS{RKBLts_w=)kWu_(eeAG@YvrPuW9viB`YC_bgtIV z#Nh6ZLXDJWg_A{teG?7gfjE6rV?#sJim;9;CO6it-cByWOVoI}^sEB;xS*(=;Sk*F z2?b_*R`@8LwM6v;-+T=x7GDI%ExZmf@|s@#FzSaO^r=CylB{fJtwWtDp4Mh5cRgy% zoTT~HZ4JAMsHzeRWdWu{#OzazYd5G;xQ_!L=}A`^T|$yd&tq5TF4SrGU|Vd=rzvtN zFTk#z5NEPv?QW$B_kwx9xDkKrB(@V8a+UG4aVnd<5iuowe(jRjqHXzkKRSaCzhH6o z*I0VEr}ZA@4tUPsL2cv2uHh-ns;6an0-P~l=6vebB-`0P z#HNf)Ym2*AQBbOJ<7v^1Xo$9jPL5~0+}d%Xu(Z>7&RS^j#x%YVYxAwgl;}Si9vmT@ zCBQ`GmeL?08TjjFPC=#VBYOvE!1vIN7ODAA>`!yFQgO(%w)-#Fa?jw7wLUw!k|T0( z7td?zNZZG5ImB87gxG3hns}c@EOb?Qd1vR1GyEg#`MZiKQDdte80K!Aj{75RtplmJ zIvD1~xHPT$;ORD$o8R*)ep%XH-cEk?G*<>W@c)YyuF6;6-wZ1OXm=imPW^cj>VfUqP&u-tyz2ju^_EdlfL+({1OviIC@F1#bcl2f zBBCHjGjw-@bPXV)w35{goS?9;~cdv8pv-jHP z>H~osKhZ?Zkc2uCk+*jP<#mlA3=X?RY62sVPL4CB2WA3x-6x%Xo9BD%$y7JoEwtYD zuuh($@B$V+aOn&b$!xq5n=?R!loCr6F*;AZzO<=aF3@3e<`Aegu!(yGRj?gV z(UXvhfe&wSn2Y~Q>|5OlWF>+gez zXihNGF;Mj#+NQYC39fHd_LRngdNy0bqlvjKTx1VEWMN1#V_Pr5wUwRNb}E34xKlC(J}aX-0)U2c2y6Qow~ zLSIb`0qVn#T-|K59OTsOkS`9X=&Y}*-ZX^1p|1=B(a>1~%reHaPnc{CY|o<^gcr&Z z{ZCATR&W{q?aWfr7!B}Y;Zt&`zE?_xj$&H6PGpT2B9ur=_SejmPnm(Bn$9X2MF&9G zBdZl*-DEi#Cm|m_wH(}6=eUHc&5{ueNVQARCkN259B^PEiIkr?$>3TeH>F?ziu3nO zq8MfyFXS>xjB?w)M*GthX`wtF(d)Ar!87;`tl9C(?nmj29)v-?uKXJQ=koiXkh#qs zCUXvLQz}euQT%C*{j|h+gt#TT8+pf5k)`3!%4yj;`cy~g=W34Yg&F#j8=Y3kYR^}} z8RP&l?W-xt=wa(jo^U3paP1>FJW<`@d%8lE~rP%6zU8^)5%ab0%|83AM;wWyh7Q4mFY1Q!c z*&w&W_G{^lv{jc9szzh9qpd5Q6(gRT(iuuq=Nt-u57-9T%D?p3i!}MrYfxu@M4(Bm zZLq>${lRE6anOI1m_Z{~=)FU0M%T0K7O@D)3ACo5+gvHN?fe#N>y(+@LhEt>zaziX z?@_M*b*lew{Qc5x8o^ZpX(@7l>tBDv{S4!M^x=W9oyWSL*R3G7H$lO9on>)$`KCt* zOYwCkiOs;HDBi1w(M*^z(`)%d5xEuoMp@*}>wN$IPI9_EpVpO9o+_&1mjJIv z=Iwyh$D-ar=>RVcP0h{qe%g6J0QUA~W_!*o=0n?@QlOGH!<3?Bz@$=!#5A_AnE3j` zjI188)?hdA&qsDdYdJ0Ex%~N*p$0lfKIV+5J@Rs8&TUA!h>MzAH_evGp+Z&MvE|ZI zJ;p;pt^!SKNVYnR^+`lNt*QC-gndzf7kGdquZZ9fHW-tA$}ix zOl&ShgnTT#)kj%!$L%5jv86s{IWt+=~840x})KcI5@4z1yR-Nj39)1acRZZ;|4cj3IYW$KCAlJ~3&TtCguP3K>E z(Jy~SiYv%;Y&t|0w_S(r`rHi;ewzBOt~h(1t{pR?oONN5bo*Wq$y7HpZ|RmXmo_B9 zC|E>F{q|f?0-_q{)A;MMQSfkk^ETn|i=ewF>H4GY4mzi%e~eyBGM*)-a|SKyU?0m@ zXSV@&Z5M$T**bfvxXg-4UJoOYqh2Y7R)79Gq`5@r@$Sw3WXzBchAYb|?FcLNYtc8= zh)vuxvoVZHf2SNGkOTS2L7b?1jw*LdKn$tL7)*ZwQJ?fussQo8)DgKz2l8G3jp^Wj z3>ZlEq?w1IFJT}A0b<3Sbg{{&qNvJ{PcBO(P#_Q}5>BMpM5I0}NGJt%%Y4+SS8bkc zmk9Y>na)aAjTeYdQtHv4#C>E;nW`OiUEJ5E_CTGwe#Urb3tRG^Kn%-1Scq&eU!7oe zUmY!Gp?tdae2va4J4(VT+`R2ExFYxkek{2h&l1(PDTdUAJ=T>>gs{{^{0x}84i$ok zyr(N$s0zqAuuxzfqK`o8G#jLc1%OXN9m*CevDK#>X0lb^1%)Peu;{{jz~lmB^2!u7 zZ!|vrs1xEzpGrm^6}vpq=@(*&ZQX%(_^ivkR6e*=`lEk%d+e`i4NUM9-wUc_OPfr3 z9Z_nIfCdmIw4uDRR;4u$#2ZHo-!ifV;j~v9f*)h?15o2iv={u-0>18cnihHEYjus? z_WdQs!%-XzntX1ev)NY`*)kzVrm+h+TkS2uHTklgKRT~5b+R3R&q|et zv1;L6vcwe3-_rGCAUODP&}yx(SOysz+|w=xeVBE;v3cv&Z?w1(E#aIdzC7~D%XjC6 z$7;>AYe`u}%W32Ft-oytE&G&Uxfpnf+5C3(<+ ztUaeMMF}SQZ;O>#zyPKw}mMb)5JT8&(`2Ty;0ocCP(#KMtY7C|09Qnk{po94Tf zSxzy;W_J$OJu|&8Kl-dVw3sR}97!jb9`X}ekkZrq{XE+7KGD!gd)DfVG`u>)*4{Jk z+Zjh?#&Hhs47%=??0nW+TcgE^$aw9BM@@;*rIR0D843;msMMe)=%EUz`DUJuU|xcX z;AeFlP1t|0<6VMW=&)@s2&z>AbJ!Y2*plU2)~$mG0W=#X82+Fi_5|&#Tytx9&M)hI`K%CWH6naJWKw=&Ao zD&0cNyo&r(d5l;in=KI4rvnyYocKz|4a+vJ8=&5&Fc;)okx@d7cTUAe`vAODghmM@ z!h)yAJH!}?%&&S%LLooMo%;oKlvKLnC#_QlS-yre7nN$iE}?R5|FvTYsAQ|E?B+>w z`*o#)7qdbf>&`own2=MyYFT7xhh$FQX*tIG0`aYhsQyTtrk#i*BG^LNf^l1?;SC*g zg`;>azwmKkeS2FA&f+#d?WXJjMrv``KCGw;A{+$FgHDm+KQ2WfB_;q94R zP&bKBdH`4f_&Zx&Wg$##`UDE4>}7`u43jd5&CLwkxve)BNF8ncZ3$S!KyD&)@*5=! zl+LPPxkG_mB=7Azn7pqnJQv9o^B!q)Rr?bg@#HcIbrBBW?Zt5Gt-tFlvY0BA)W}3l zmFeGQ=vAFCoVw*0$Oje$^p|uut_iyD{Yj!qk$m0!j_Ejc?FCyHjH2f`r_<`vfrNcYIfo0-u)k=FuwYy5mm9Q>`sW;%DpqkD{7W=v1$<3j+l%7*K zlB%2fl_BYVr8SgVddXfb!U^e`ZP3H@_@ItnH3La>^Jx^epab@k+&vU3;=E zxjmpUGuVEG`*a2Oi_F0Z&q@(uI_hyKbIgvZw`u79&4lw-S&S)PCP!HH0p zi1(l=etK$A*E%Pacr6+dkyxK(XtZOyRm<0N<$&`KoM&8N?&e%q94KiC4E(;r5nUou zzFZ&vKL@_Za6x711g|JCCM=(C7#uG;7w@{YBV{9H2SP+h+9k*+FfZQ&8IGT=%lQR< z+b0z_W%T+y5%Pp+i9vj?(8BxB^R6OG_xqstlt@M5m1o0}PFy@jOIk|>)WuOrTnKz< zKwA0{^9)9j1$+Vi3jEsS>YkHjUnH{tcu~cT|1h<#=uVdV^^T#dsL85~f37@WkWT&PU$tyDb7k~l&MW1V8l!D5v?b%jP`;&fS zW{2VlZZf=CBlQW>j_rTum8d$q$M)bIAS47t4X`>@F6%B|5}9RzbulMk!`J$o!qQ;R zN_{(A8YoJzsZ$%H_@5dj5xG%x!dq#CP5MG&khE;GBA)M);a3Rvf0)toBL)lBS(z*#g1AqQfIB==!H!&zmSwSGjV6nwJ&!6#5i-ZaX>CLbPwY|yb2jCVcdk#qBO*Ha&w0P->Yc`+8;>sS(_+KsaDyUp z+Nk$GQskHAuJNhY^!D7c9)nxga z=!M`5InWCj=Wa$TGtQN>oM@35p*rvJWg>#;vt zYB}M8x!hVB^UEbu(_p8q?O*#dzrV^EVw-gps_sU6$27>b`wQty1eNYi_!PI63;3IxrB?EaTd;S)prXGq>(2=A|0*<7H5LCqZjX;X&)Q{C(8C@BX}_ z%l-Y`LM!qfcOGEm4apM`OwD7}_O-T(lH(&>AGOqI5y8LM2Oc)`F!~sz=T2NM-gMu< z24}I;+X_ar@alZAq8aV{QWK?ynuad3)MNuAVuB#|x-n|zSVaoy&Zq8U!-mPVZq)fZ z^ogs-Rm{t_X^T9bH*33V+tu_a?Q=2ybI-l~G*7pML2qVUP#S?NWBuMStbi+PvG&K) z3-4o6>C4MGX;G=88?PEUkf`)r?B&0(Kg(B8qxz>YPP3jBmlv)9!?Fd6>K;%^)m~?7p+@8KJQqe zLH|Z&auWDpWPmas#0C;j0%;k7QH2gfD&U{SRiw#~M$>cXTVQ0?4Wv@yyj?&@$aTR) z9Xj&L6{EcvSvpr+od5ft3Mgy&~C z_io3IU$Zb%IXF>01cQVXAdxJe%_7DzYnGg;LGMfH2j;_yBOocH*|f(ts2Y zlj>(b-$IMcjc?AWc3%&$Rmk!*hHVXADuq7t59-4{t?HiIUa`HGXkp7^?TMj9a$Qib zXglSseo^|PCU#26{}4u;%mfpJIeoS?P!&kI%lm{VW$f`WQgTs>%%;ywND$@t zy!f^CQH1>#0a)%981qPDbT?CNaLKlLY5&cXj5wZ_lCjKEmrW5O2y<*g;9%#jm6{Y) zBh^+;=qLQ(rcqMxv`XhocAHfdSg>A4|}to0XoJN8{2NINpv^ zySVY<``f@f6O`Vk)1NjWJztlRTB$YC7c=B%%l{zLA)fYUyAuOZla8f*jJ_V@Qb&99 z$iSDef-pZb^)TW+@0fX)#e$v7o_ma;_(`&4fJ$A#Bwe$z*WdZKEir;x8&eGeXR1lU zFm8`wEee|yIegFM{<8pF|;oul-WIqmU z^LhAYA^)laURvX20jnFb@l9PHcXiN+0Ogk!S9xf*miSe1Yb)y#Z}dO=P8=}l)-RUv zLlw9f5$ADqQXln^EA&-8+Y&t#y0F?m&`-v6d7UuVD%x^%<0A`?J?__RZn>}WPQI2t z54^j3Zgju8-70KIpL)EaCneno`Rs=m6H)oOKM;4_{sQD=V;yB%sLrK0i%a|OuC4vJV`5SKdunha!Ztta)KRL4E&>6D$Dio=neP54b6j0(e$HrM5Pip z2g1+I5tau}5^pK(+97=~XO<)DIzyZ^cCJmpew(+TiOH=HpV z*U2A@1kNg*egz^8p-EyLw$Dcdi{eB{!hV;F<@Y+(hMZUO&fw=7#TSqM%MUSM|lZn0YmjCu(-4vvFR+H|F&8;amL& zaM3xvv2T`oMjH7%K{U3$ZLX5w2d+SpC%krujex9$Z zaZmYR&_kAmBqTuzd6l<~(;(NLb1|`BSbq$7M<~IrXpIHGgEVn*ZdkAf6%jN&tq)`P z41PO;qj$GZbfkW`W9IiQ9sf%9Ix8yj`rv>kX7Tb;2YaaHu!mP@HpMfG``1$b^LEAP zzR(utd8vis4En+MNy(r#@HFhxY*me-+VPo#6jKmgLoi&=AjJi8Tp)ePKfCCzZ#Hf% zDej1x-McQ0N)tC9mN-Mx_LE$%3s~mF)qtvYNi1Y%=_8)iS1}u_y2Yoo6bAlkUVWV9 z(4e{U8^Ro^TC)7GtFpvLkov-A>==qL(b%QEwm3Bk6&dwKG?&*;c&SgOHmzTCQR!xV zyx*3-wz-Zny4I{v^*ZXc0vYV-|Anlv?}ybhj?s?o5gn zearOR$CHv?))xM&J$&r{jVttk$mzwI+23$p{pp>q-ohjSsiQO3z;&-ize}Ov0*TBczrJJkz(9sc z4pF9czvN?+p)jX-(rq!cr@j92(;)&4sh!H-EpUd+%*6?&hCo-p)yp5p9Y+6dHUtqd znUzLY?bLx1B(4Dim;AV%G^PqzfZqvv@dxCD{d$!5eoJuENb0@xi9q1s*`gmBaKIks z0E@s21Qr^GVH5nJFWw7?ZJ7C9?Hu1#M&@+3<(^(3a(TQnSA>7?2ldL zWqJ;4#U3!we$pY<9gM7>sV;2wJs9EiIN7i(Ur-`al)3{5dcNoO{CD#U6ilQAozfB) zD+@FpamYqn5K40B{nI94WP@oGngXNKu{_dJfalEQ?QiH1*%$^!&w2&_PYj$y@&rXb zjGQ*M9luY&eKIOdtQE3y%*@VIBb0sbDe_M23g4+_6zB62sXIhC)VIfrvaFpJk&o;vP|2E=8z zAnN&mRELHmJ!3UP`Y?k3>jkLfwzthO6gd5;$}a>>{F5`GpaxVYuOBbh?F%KUA5}k0 z!IWLu{9yS!Z=SRJt4V#Nq~~4tyVr)A6~LV(quVVGWgvDeg|2gE@cK;D&-eCp(m=Jv zYS=Msn|dhIa|+ESxHBj`{{p@LfuPkWz?@=60 zX}l*i)TAChurXUX>0xIb6&7MX-a_yBx2K7bY-r`!?KpTk_$!^4T|ayfvb; z(YSH_A1K_`!B@4y>P~Z}Rz!9shGPnA|CDC&%XRr&fs-JwZZ6r~&G3Di|5{SOACB;z z$r#3}#k-_dGx<6IP!A_4bNH3D=vuh8H_v6>Cm{~s+^N}ZgLM!M84SWX)T3yL&faj- zUyuEUwBAKlNObIpQbm-qC6Z)HIuXQV)=U?%#H82Fq;PZhRqLNmeJ8-vk}~0sF%3Vj z8fjYr&ib~H{+UE+n+MnjEXH38pYK!lwu-j6-t}FIXSN<)iXW$Qy7*@f^IqN@X-Tx& zb0AO?;j4?Tq^pd*lCi$b=NP(k4AU)Ix>lfIc*^N+zBLuib`IMMngeU+5&VRlP+I`~ z%N*I}qz;#4NxIuXI+Y*Da$f*&Tk1QWP)hq6=PizClZy9 z>boZuRhg1}df5)&FwioyEjhPY-rSmimCB|HDR`_g z;XnIbNu0&xF=bC@9d9dR_IL0aI3GFt6-HT^Mw<^?5@R>e!<$UeB&QMIP|GtXUc)ar zsa1r`Sq@???JAI|>GsvB+xuF6@eF6Cv;G=OkpZwrA0xS-<7c1Gy~F_>ony(y|CFvB z&)}(PDH^^OqTFk^lYz)3z0}ei>f8qlWsTK1gQrmI%;enx9Ktm=W{S@j3G=?10CwUZiv%9s^X@-$1gjCvsl~C_Wa9Csg%1{qvN8_ za-`(#Xnmc>j*5hBww$ekZhOV`yTJsiBD4K~S*hzCc}HXwv|{RH6{4q8f=U|Rua3x3 z_b~Z9psT}{ofcwC&DU>=7mtPu73elcYU{u}WMU4}cqc}-XV&l#+_icGIU62!I4vgM zcq~0=zwAekU(<6&l~r`Gc3^!%4KIjL(aPv%>FkgzxG?S-7Ixc*yGQ!(sb`)|U1slW z2kyrNF1}-xFGZIOf5kt8E9y*Ky1gvTN$?Qj#E*dBwZy)uTA7XB^#yPBivJ*((9+#G z`Qh#BzZOeH$3=9dAXx6@dV0~ccY0oY_YT+;p5pfb0Ozn?+RwLzSH)4yTqOCWf?Zjj zy>JrvA6PXI{J-G)ADopF=mY69S5XwLm-}-}qKrp=?~R(){bG-0h6qHNR{h8j&u|@f zaij)7zpZ%x!~RyE!E$Zj3(cU2Yw3$BfFVTWvscl!HS952l!(j5n${o0XgBDwg2hXB z7Jj_?4t#1kPCok|S53@swZ~0sA{cB#WV>0~I5q5t4CHhG1!bUDg?lR2iMcnW;Gc~a z>_n{=zGu?~JMCRHK1_Vh+p=#XWGkz8vMk7>@^~>yWZursyvMAYDf6v{GLSj) zhQ~tA_ET4&00c&2olLN88Waui)qhG)GdtVi^tZgy&?8n4U=oIe(0CklZ~LKxTSHTL zOVhz;tl}HBGeXTn*WA-}Y64hp{XAM8`}}4PZX$KbZW6y%IZm@ywd>6WjS89((g9@$ z&n!)t?G<$%r}2+Pvr|vFionnm(QyDtL}RNB9Z(vAgcKNjU_a1%DZbHd*`}^Di+m56 zgKIJ9>qvux6&b2S_H2Jp){eLMG~M{1h!f7lZshot2MywL00zswn(N_@7%Kc0702ejTv+w<5x6^MYS;4UPG zLXE#`Ye!8;2z^tk(Ak}hZuxhKsP5E^q&xg){MV$RTgkcNGn)C}S~F0$E)dsk+05fS z4mONuIC(P;PW~8jV!0w{#}_njCC<0LNZxeR zAQvzayHmlK*%pEc^ulprD; zig6}h+I7>Nn3@vde93)n`uKQJXYOw?gaEdZd_9GfkJ^W)J&Iuc_EP&F)upmHiMVxG ziz-xnd_Vm54P^hcYFo=;zue%=uJwZREW>wU)5U%1G--!`;7-3vyy&*9=Qj=9OBFnY z0^V@j;-P0U?zd7MZpKrhGT^nF{5rmhn|h8VQ(p5Q^kxMA#d_K(LkaK@Nx9FAGRW~J z7GWk-I;D(=z z-ml;IvXoCAU9w~v{kJ%-9xJjT#*$JtIe*-Env7}s$;DqkKbOzmJ8&{{m00!aJyh}I zPx~)Fl{0M#c#s=EOsc(lQ&|MK8`UoFJ%c`3HWCS-0~vM5ito0dTJ6*~zxzA}Y?D3O zHYxr7i}Z?=ZU#SyjgPok7Qir)G?`WCma4jS`+Fjeg~OxHFo#k^SW**ViKyOjkI?OK z%+p7_L(raBJkneJZOBuR9{=;$yJ+j(yP*$|h+Ws8k5V)(UhX(6AH>8$PTUnG!--E0 z4je1Q=YIRs`<+sX2j1CZByTH8F#_&V-UHiaARnS$x>p+j8O+a0kLZ-P9qFxIq7AAg zUjIMKwsRmnkh>@eDu{|^rK^bvhO)7O;(Mm9sq8zpZ-9R0vBNc9dVE`<8k%8^6~cm| zZ$SbP4%VsJZ}BT3rDv(&lgi}vI5MC@;7^A2LG{Y%M8t-I1p&rN7VzFzDR{Z!1 z{#&YH&!nlO_&#-azjKgpr8rP~I9!scoGwvb^D#PBv+^qfde*CMwR=+!u-5ZD@#ObMm8~7v@d3Dwb9DG+l$|*p8R%AKe^=#t@VZ30 z3!E(u4#Hh0KQyCFcMAhgX)p}%reb6*l*(-wUP>uS+;7cX!utj0Z8Rl{CRz-Px!mBZ zSGjU6bx#^Uv;f2J5A4_CZ?l@Jg%pFrA&PBolaLoyp}(Rdu`e1 zEsS`*`cz3ma7A?*{B#K#SF9S~g5{x4MI8#TrRFHtPm-S+I$23Lg|>cp%0$VdlcwyS#$$?*&)_gj)f^Z}d5{_~~$%1kYK2+#ofaaYJAFv9bnYvw)o(fU=ri!iDR_0+9iLy#=Q1aDMj*tBex z1F>OiqLF(=@D0@B@^|PuHE$fR_V>Z6`#42@3ny6x@{2{OF7osYJk*!$WU4dFmz+i`z39!S3tUJMaA9_v~ zM_mWE@pC9354AP=fR1W*o**esOOhbc0rTxDJrlUJ_ipH(vMOS zj=#jZie=#aYi8)WfrWlBYE*z%4kjgn>JVwct%&M;svU|o36HF;kYXYawT8K&&>b6)kKtHn$X=}f% zwYD5>EYS=@8$Q?Dr`wvf+Hcu4o0y*96g>Lb>~p9i{_5;!*<^o4qot5^gClj!r2S6r z(eLi`Wb?nlyzR`SKVv@E8b&lGpOh3Pv<#m$K-@E9W?O%y&Etpp0S-XtI$!3sxORY-89>a#fqNJ-5l?ep7 zfJDgWr=JJU52ty~W%t793A`EqKQEm9SA*o4en3uabYOv-+T{`3ua}m@_kB^jvz`&M zy5nEj7>dSd`P%6}dX;@F&45@vUII0OdQ=G9zz=-6wPhO2{U44%s!F}>i66<6$*(E=he7m7l647mkQ^ETX6NcM{P@4FwohNWy9H0sJ0V2vbHUDI`?cx2Xd*$l zL9J0Mka1H0@X~3Ok#oZmE9#I)l$@#N8zHEfQrfI;yECM9`{1aLWQJ;cC;t##R#3wm zO%R$hY3Fcun4GisIs3{X={J3Xa|tukq3j~*{+!L&*jR8zoY2VP{%HyIDeaPxr)Sb6 zd5hO!u)Djv_x1frNuW8o8MWjP$OGKnarSG)q?HQ+=d?%pf3ff%l&n&?cQyN%ROVgNGX<_&i1;#z4~uadzP%LVAx8 zpXctzn%dMGbnZpppHqDp7w3A(W20BHGXgvj*oreK4ttoD_UjiirzhH>c!2lZ9pHaq zbhDg}bjzBbeLwd_N$e0PlDAN13qxr**xJsuTz4vZYOF;`^F`GFY{t=@|Rc{*f zCg|}&!c_nnUeH5dB_mV47{TKGBnn>!u_2aWJ+=4HyCL@TFMUa@6z;yiKBe|8RMvQ= z;@*VPc?`i{$(I@JNxrn692`7F<~YG3NIk4o{~)fs6kI$8@O>NgcXx%3XphV{2b#?0 zwpE_niKBg;>cp=X%^U_PQ!_G=6#*-ce6RjY3Y(2^Z$gUx00%Tpd+ij+KS2)io6E0y zf@ESU<_c2Acl&i=%%>L`h$T4$A2a-%bDW@?N|(QuLvaIZvBo=&DaVWM5~I74eEgAr z^Z3@?MQUi}$I78AZnLR54d-h3$D8GUl*V4~rFZ>ccTFr{fdWENQgOV){@l?3EZFwoh=OrYY3h+TmZ!z`8B-i_h6v`2NVmGJ-MFohaP^g24wvxIhOsrZ7 zLk-^v7Ybt>ztVr0YS2uI0Ww3TOveU2gG0&=ZEBdjvssi` z?>n9hx4M#&=a3$JbI5#-*&E`A_V1#uSL37~Y?MxlOsyr06}MEpUMFk>S?83=%^M|c zy|cHUSjI9r3iJm6`{mM=uDG_wzcL7*3aOz}KO~Xhe~2DOcBMcH!I1f%GZ8;br)eu+ zojtl%u0sUvp4h=X2>3i8tbkFIe<`#0W2mOD$S;ke6itzIm?6>F65)u(?u7|%w!K|^ z`kZg>zWSwAE6LU!qs8%UpvpnES4GRkjTqwUU`I!rM26a(a8B-G0xo7Q7H2(A9R*`! z=RfvM3yvAB+QoeewH?%SWWF;QNO4io%|n$k4?dP}NvrZ2fj#48PVLr%D z-%pG0uMRRydQ2l&Iq8fgjYTyOKH$l#z6!2#Aj|7?P4}M47J26&&8c`I>Fadlm8spD zHoE*>#ntG}PgcV3QsCO*KBIWa8s65?gk|F;|7{0{B)FPX}fzOsOH zXxi2wFS&nhuPHL)$tdB1TPek7-K`VF{(F*Cwc z68Z+Xc->tC3e&-cj3tP(vtoX0^@pf82W7WD{J#!z#wsSW*1oPCod5mx%|}k z$$SffvM#)SIRhK6>`5BBnCBW@+3-)6crAbxqV)apu;bYTiA>xI`fQTd+pl8o)HZsb ze$hK%?J}W)^dk22Wksf2z~H4IZZean^(*9rZXU_YJ2ZUnMY?+TJ@?KMH7EVQ(gxi* zY$!%ldi~~te62?bx?!}C4`?Adf-*1XFkPBsL<}gh^FN1XGlMZ0$~=HvP*uVjW!Ptv zN%}2=aSS&|V;t-rn|;m=4u`mRAmOpv`yZBSa>bGaYQ{*U8$$g#RYb?DNfL_OI05a8 zBqnvO)Obfj8KVC@n!EIFZ*F`2kCANn_`I}XE!3qsm#)}e5h$=Xvubz7;#sok!@?fppNq#m0w*psrZsr|To#?y3 zbcTg}254X`Pz*fLakuZ341#ppED64oU~;JVm%?u+`k$dn8|(A5fc!yKU2EQ)q7NpH zEwK1h4;*)6iCrlU%@VqM7Z#{GR)2d&CErQSz%8Cqww+x) z%)SL2j)CIEK$n1rDnPR}PCyf@br{2IjwMP|Nc4sA4}e=yt``ot{;@U_`S`dDRHznA zBrbFUeIn?wg)>`dlEL?0NdVDCu#elS?}>WK%XO9X6WbL{2rfeBWAKFa|xL>b65@i&xNC@Vv@Rb^bP z=}iK()EyI{D+F_XGv(L=tyLy^t38YVHu^lw_AfTqzM$UoJs0yvtjcg$qliXilNI^1 z97g53Ur>mkGn>QYtX^&Et!U}ESJvZ&Vz)H=7_*O$f96+s832$f1ZW>otcrzw)o(cl z=tHf{zo_wS1FC^kqcrtFLmg^pJ60=~s)9Prp0YFn^4Zs_OUy^Cw5())e-_ON!VH$< z;gg`!b}Ie3Jui@|jwr$<<^GoBs*SDqVofMXd!KHxN)*#X_qb2~Z6_W>C`h#E%cl4i zzP4r(<*e&6&9_1Rj7JY|?{XFoy@)H7jdI$ft4Mr}xf((uS)j+ei*lD&c+FNiJ*faO zw>ECn_xm>t1B>=Chj!MO1rd!7Zed~Fp4;kSt*D8HzoL4v46gxBz}SM!wP_1>QECTG zG8(86YFE>3!hCIe<=KO8^TKYCzFV&Z2xQ$K)^pjp$c-zNYZXhq48n}nxGiLG{_srZ zz4r8&8uquZh@aAIQ!PqR)MO77A1B#jk+(P1&v5LVNui2NlW=bjxY*(J*tp1DRyx~H z>9H+rE&bqtyMTXOPFxBXTc;7Ki7E{5($D5*j?jRR~x0|3@rJ7H{UFXhKZPmfymgg<4>m{IL;cL1$&eRFlJ-fr9oF z?Cz)r%{}|{LeXpH7Y5CFK&dBgVRX0MdRO9cPq4UB5xDgWe1@&?pUuy=l6>d<2Ci!V zNWGJ0mO1fR6rT*15qNy1T$H{jjB|M{T}0FVSXUYvH;zB?3{Vs_Po$eTVn|-E0`lcH z)`6ML?kYMx!|MO2uQwb*H!yhnRlHs3cS%^`=+V6M`}Kb*U+ggkI}A=@L!c(6oC1cL zR+Dc0uG%@yhv`mX(J}N)q4+rBm+$}6iApV8%(dls2drNH!1bgK$LtdVG7}*u)T)5i zwq4yJrmU`^e?;tShZM0xv-S%kK-8M0BEb;d#Fglm9Yymu41oo{a=o;_0gfytG9 z-Au6b)t1B{kB}_=tPYG*s|!I zLXYbfD+u9tS!S9g6uLmW2RYlA`+!vuhzRO6>`)hmLAP*J>~RcRqE^5I{K9#)#jmu# z9MBBgLhnB=)ejr5=-u@p#fiPmNryks1sR2@;y z$WS|vy)D05?@k8q7T%&uMYu}t?BJ8{=+$PEZlj{3dzXE~WN(WpmYNEXaOlN$#da-J z4Gs$GIMOonhC1nBe^rn=DGf`dtTB5KWM9ktpI&Mb zExd2=%H5%amF`q)TC(I5jXaER)~ximl=GBd4gx#NnUmQnGkNn#?gs{3 z@9Q655;$Iugn7)O_gXZU0^wADc1gzLiZcr%H+W5>3(s51KTHQsWq6%win}P^R&haX zg3PGCk+}_m8Vm`j6VO-lZn2YFn)=Hcm|(ERKc4^#GtC1Xs79q7Rbf}glm26*0@~C< z1yQdGNbX`)cV#QoDR5N{F^qW8)ItcwsoV%{c$WTFMWJu2mk#5NZ@c2uJ#N+>`QA>) zA#2$z%9imi_Kp{i4NSsf`~^gN4af>#av4{cF(Wy489erz&!-o!Zg4w$XvgEU zYA3(#N8BxcK}74Vyc^%@KawT;eUys&Q{08`?>6C_Ildgx&nOLL`@?`IuVlPz{ejFY z)Psnkf=iJ&vRTCKgYB+TSKy0CzgsHF>wJ`*cL2{(76t?F`|9`U&a~ey)c)i!53WftNe5{9KhM@1U+}BQZ z;`>cKyYBOewJPt$oGF^Df3!R5XmzlWsYZdqgEF$8#Sv*?I)KRw5yZ#2T%O*qj1w}* z>p>5|N`CDAcs8av(NmYJ< z(+JhNB|U{3xW10a@JwMBh09O1=$hH?IT`IAo?X4Dmvz)7W!v4_`927605(Iopn7)W zHQB-Q)#W6dx?$hDw2u*V<6(wQ)Z)4h(Pp2>lBG@>TjdNE6p<08d_}6wB)lAd-pJ|K z2JMF4)^z7&fnf7^pBav*Dn)H0-=W9g@@PCLcE4O@d@(zhn5Ji24_H1UH4=^-4I?Md zDdrX5j@8_ErL1()9u`QvkrWW-_T6OB{v>3a$*H*Uli69l!F+8<$c`GYx3gUvy-+Mz zD-72TL}}&`8LHoox2&McTC4l12~@^VXmtNML2^MkcO?3d$ zVqT`NMhE4Zm;BVg3j?1Bf1qRn3l*RjxiP`xl=Qgy~m^@NW^K)|e+{N{J_#Y~|A zMX$XYu}S>D69(B`9^}h55`_yvJ|I!H-V>RHU3qg;?s0?&!^dVV@dG)J0kP}eB`HX z=1Xx$QhADty?BK08#e57UIj>b)B955hkMoN{g(cKJGad0dGyyNR+gXO$1O6n`tH6ICHgH5l&+2NIpmAk%7>LZE%W3J&EiQ)f8J4hqok!N&< zI1}ZcG`zZJXiK<$?k}Hs{k%sugY>@w`v5bpBaPHes%hqu4-2?!=M7wIY?hLB@z|F< zpT4_ApgkoX4@KKu?UsM75 zExlxesiQKdwEj>yH-SRYi6vN#aohTqz^+sYk-Ks2P^)f@euZBK69@WWpa54@Ym=_b z2l|hPu#STYnxf6lRsD{>tvk1GN?Rvgn0!~S3WJppwx8L#S`j6ibrDFvO?EHo8cP)j z;ezmSr)6Jm0t0S&14#$BL0ac1UBfHKoZmBrDqm-0xkocp$-Rac`tmS6K9*gc1&y!)QhHc{*Yu-Q&2 z{su%Ty*e#@^#K)b06rE zcpu3dVZ~DF8jJ_(kRHbtSXT2#XkQnu7R||e^^o>DyG|#MhCi1Wnfo&EE%z;z$Q7y=#R|6405>Q4VUmCn+`l^&Mb5 zf`^;4K8pA9Yh1k58)SNAJ2OD%BJE7Xo||u>Qhs!sPfoOOL*1Pr>$scI4#=~|1sw%A zn=)_kOa#Tu0-D^R&pgkISiUO{l~agLY_K09I~iJJtdnl|FSrMr7E^wW7ZKKBjb$Ld z#-d={5XotY)U`ngK1BJBrrW{MAbvrtyijtNenL`(_oXXT?_xTLdNX7v z5REw6v^QDnb#d^fuhT|ozJS7m&U^w8zZg0$vo3bKePrZKQ7u?4lj>(HRsMkCf-{X` z9P%+bQ3EnGDdgyHyMv^s-%drG6ulmx-7sxSNzo1d9%-{t9){tOi&2n6dX`3o|LmF_ zoNiG*-!k+)s#(|2%DzTefi{wA1v^Qshk2|dn+lw35nIC-M6TOjEyT%Q>awgFH6=CK z&R&l>_wd7pjLf5PBcZF0aKEMsn;$xa?N4~l{#tTs`04m&Odc2$Fj&&ZDS86qSxl`7 zJ&%}KV71J!q2rf~p}ptWtAfeveJLbP({_#0feGCN7RUpQc~R~|NCV228aG6M&<64cc+gVg^(x`X`om2=y{pYd68zO z58)Gmw_FbftNXUH^JUG&^hbfP52pzbrT5EhWjG{=R?>fEF~anKGF0Eu{{&kp9QXDcmbwlHz3nCF?HYousC$^7{y{ zotzMcJ}T;{`4;wfdn5^^B>?VG_Nt3r^q`(HTz@d{lQhzz&}Osut5LjmLwagdY+ z-(pnQx8(*KPg4{)x|QB@d`jDE@_fo6rYDN6V#(%$`q`>7Z8b$A^7-?IOrzN{D)->x z{B{XZ^xBPu0n*T{i52llmBsAXt#@}F?u!q=LXnPu{8Ce{MGGicj>WI}m6b?P5O92U zBx1a3%)m>)_6W!&F9QN3!5F<6Eoe9 zr@7&VB}Um>1_`?Ba;8;=4ajgbH6zdXkGB^fjL+oQn1j=B)?O$(&%)XrMi@~F8HUQC zrZODM(4bP2VZk~qIYi9OSKq%Rsa`!W?W0;|+*ti^hw-~M#B0alknPx;tb|g@=jGZI z_uusI5LqqUL9Xuwm)6}8SGVE0cpmm9L`SX32u&Lf#F{;x`U-CpWEGHUpFXZ0Xknv? zjXNv{*cgT+CEVdG=o3^IsS92;YnEzM`p%UxDuoXwiDfuMgn`O>rJaKJz8jyBO$|in zLJdno*46!H3B!t%R$4rU8nSHMJah+0?6kzwtBKUrqDd9I5{az(dgkc)RBn?J2TQA* zw3a4&jH0g~^bGu3ADvU%Uar;w<$6f7EhEHW7R!VP4sXNSc7MHk``gbt_18cHl_L3| zDLY78`b%+J&jp~g_3pc4VYuy~WozZKxzQp-)cH$}t>x2{A=e4iHi)TV*g9@R70!Cz z_A#Re$41Mf6>FZkkJmo;5LvfC;m+|_IzfL8dG&4F47XNej(Wq+w3}JEX1@s}OhlsdknJfy+M zAMXh8?x&aJ?2fRX_>Q+r&n_?bpPth>31OYGw=5(cVBB)jIrSNAvnuLz23SSF{F9R5{8FYlg8O#q$%gO!PlQArVXjKMTa zzy8P!l0e@D>1)NQSYQqtdg`$2F@)v-BaA_5^O;Me!@rDoBRP@IP4jT#p+Dtr0{Q_ zl=6AyPl{?OM~k`TCMQNlDsm5NzlfdDl2GOqRyja0Xl72dAA#m5?I3?Ya>!y!Bhmjr z5DB*>C$?faegc`%VP#sCZx?0Ofg}zaNTp-Pf@(DA!cb=%%o+s3phJcbSDX zY_94&4+*yKdUTWEO7B?H77~s4plg4MS7Xj5ni($2fkox((XXV zHsEq*xfy;JgnD3C&BdU9H;Ui;WTSCneTPB00K!bYQ(Jbd<#W{ovAq~;`Cgx+IeDSC zxZq7aCiJ>D;XIs;ar(gsS+7>ue^qAIHI(Zhk=3_};rBc=LnYdKZ_nF|SK4+>A~{bm z#M}%pXH_^K_-NcHe(zD$b9~V>toTPrxS<&_t{s>y-#G8go-qfNv(LtCwefc*ex(E=Tugc;%PzA`c!y^`=T&^$ zj=s^oXXD0mti(DADu zDQhY9nKx`H>yG7sgH@5OeezGzosk43)qhJ@g6e(7wtUcuLVQWIku&4mRbGXF zejljjvjs$wdK@$edRcZn5Z6-bUbob3ano2-?T%=wqor^YR65KtTX^E`ryf=bHEX=D zmo(BVA`Ea70P&)-oOsDSB;(I5yufA~_$YN$;NrBYJGEv5{8RhcOn+R61M4-wwlT(T zGe^YWC|k~ZFrFvCoq4!GrFz{vxrkP+MfrhQ*B|%NU9QP;Zb4hLTekXMuPeX@o1rHI z`UpAMIKl$#X=;%?CNqMc^x0j5817&gsx}^Cwt%%U8G|70{ER2sTqD$aP#7E=$O&$A zdk_A(us3`>v*&o{GCCwY@w?Cr8&`RYnhgxW&l6jR?OP)~#>>MSNmSc*if>+aamSDOIrd zok4EhIchykj_-ZvtYX>H$2(<3)a#WSkAU#+P4bm_;0U&2$|rr##imxwhw9D0!@ety zXHGk!Xvz0h?m6f@P&c0a3!$5)?v2t+l_|&*(4nS&-=;g9n}(@j`7I=aHwyOy?=xS> zPfywJV2JlxcXDu*v(lw9cGqnMi(^jf?;h@u$!{yWrN36xy~Tg(x9GQ7Kc0ka%cNCI z&WIhN`A}1olgg>1+T~Z4z4*Ehs}0Cq^BDzOB`MD&qKVrXsB!1IDH5mc*jn*9Wy)%Z zK9h<}*XWw{F~A1mh0tiPSniC^>GjXP+B$4tz0++ETzzS<704jGDtms5m?(nm-`X<9 z)$0no4{592ubt0lzuFuL{jG9x>31rpd`#9lI#dms7PsQsYhKj>)O~U4@K9W+O!tQk z6X!viF#Bh!0D^`o$dK8;&!kjrC?R>d;yJCTma`un_FhgmqbY2Tbo{W{*2fC-@we;< zn%umoy6>YgTp^EIZOb6R|K(oD#sd@{KumL<2g&llVewAftM=L#c$lP}o82=KEHo3ST?B@8{n7#}e)2h-_8AS$A#7&3xOx zApe(<0+`?Bp$yb1-_P<${o;9VYt4l5Nyc6qp@;;x^xe<>O* zu3BuA^JQPBfSxvXZ^{~MT=Hc#5oyDhW*JT zaQ6?L#Zi?-q^&p){-EtnrFbS5DA*AALYh@(fJ;K^h3!z;ll#4M=38&rL)HgrGc$5# zxQ<=-PMeIQ=l$lTVLJi6^L6_Rg_nA9PSP)3p7*xP6*sHeX&GErSGm>#>1>9Y&ps!Q zRc)DU@%#=k2c&0=?fF|LjpNG|F^zL>KFk|3KHuFA(g`K&f=PyYub7XU=st~nkRXH^ zkeHoBEk1&Q9Ct9OO%P+Ru6&$IJ>k*TUFft4_auoec?9*zI+qc8o`*TtI#0v7M z@PD?|OCzRJi)Y=(Uq%v6$?5;Sm|l?0{K`ObD&N{pH9wGpw{tlKR4#w1lFyGAFE8;p z&9+nY-2X8{5L!0E6BDlot*<$4YITrBJPT@CE~|Bc5Lx`2dd&Ge@9tSEKw{hl_!!Mn zgk<1B(Pe;qlj3i%t~bFynSirXYo}QKy(hBOIMm+v0x?*7Y9qC4C@@#Kj0fO4K(gF) z)8DlYw&E9+3bL5KtE;U$n>3^_m;My|PkCfj{s^{_S`f4AskQx8ofL*%($C8>1Sw+f`hv zlB>o|=ypZe=f)?Uhgc`*pn&b!Uyds|zOHWWHJ1)S?lpD2k7j=SD5wZ_dgG=Z8Cgy9 z${UEs{341(v$^E}3F8b;_M++h17AJS^L--x(mcLGc|KZ~Z?6t1RNFTan-jLSLgBkO zZI|#%uPW;H@0(`%!?&MU^P7)9kMpKw8r;yo5Qk9RaCJ*lzyhZ}Mgo44{|LL6Y1Y14 z^(2U$yR~Q^mZ+(+MAa4yXa}z+n@m#n9c^I<>-ekWYfOG#@(+t=!AD zT35e`2fM9$l?B00iRx&0kRJlk{P?u%W1$JNoJ5ANwyG)~p;Z#H8R>@`-Bm%M6jdcQ zh{Z0CCN(TkX&}xMT%{79hF=g7X{_Kk4aZo4E%eUmil)+vGd#YHNk~lZEB&@SOuRgu zE>-ezno(;Xf5r$MeW$Dlp*?`_ z7@}QXU1Omb)LvlrQG}KhWnioCPMws1IYqzToNYE;8rwj;`*^dmtT~19DC)iMG%@T? zeWNGdV?-K%Iefg8_>?D2`K%K6X9Vu?#t(rDcA3>=6!a7q!~IBS!AA4imwi3&b`iVF zMEOeUdwFFZ=3b4xvo;*|dNLy!+fD%Ud*$E8pQ)@!$Y0@&`cm<^9bwJh?O~^TJ2!oT zi6_H**&ShF5BTke8Rb=%$)8B-!;GGlMwfl0rBsky$oKDlH(fM_kIu=#d*FYzb2<4{ ze0M&B{B`pI!+Y6FxQ^}t()p7w_%yDkIsZO}rx&Tio>!Z>9zw`4QC-_!5-0m^Ji5bB z`k!ODn%BrO-f>UCF#WcCY?noocC;22sK+L4IwX= z+p6dc1Xv#c(k;4zju$ow84?0KVPt*kT!vTS%`H2hjUOsLGpSX8QETChTL4O?Bh3-! z{e;K-9Q}AejhSFj_RwRORu@QIgO6Qz8`zveJTS!Od$tjd&1^swEAOrvbd(I=jkicM z8kz%q3guI?Rz0}86jMD--W~F7TP-(g;RI=y+r^aQQmWIINQU1Pxj|!oX8W(R$_cZ- zW^Nt6N*l)xMRb&p%?hW$TjBZTR9<+!4gjIX{ac?wfa8L1PTP?0F@7@!qNjd;p|tHI zC!ehK$CfYt8Oe2Q8tzU`C6P@oW$jNLkAnxq&}Rh{YC;#fFNTFo%wk6^JP>Nv{s|&e zC(tqI%8M51G*|*QLZ&}Z2UAZ!4STQAXw(|b$+G5AJXAolegVI>x>``}g(NIamp$0p zyMAa%asMgCVij~=7F^Uldqj(^VAyTj%&Xl!Y{4dx%BkBnnfy}%v30xFY?YSGluv4( zb5A`%>p(>hG@u6a5IR{AamAwGSD~-nA|pF}_Z9;Ck^@Kx*kt@sOzVEqzuUTImOO)bGw{rO>Y1;%8Jqo(1>O3GIqMZamc^$4R0(a%__ z1ys2HPuTz~Q=^Jmwrpokt@7MW=rE{bkTtKSHwo*R1XZbo*V1x&)t~}e^OUImNjR3w zlzDl`eH#8wXxz@m1b@GmJFn$J9`P1J6B`!{Oy*3#f_9G{JV{iLaGOvvJ$Em7=5z8e-lLjv} z$c+!h1w6YEn|WoB7uIY1%2D?N8%~}dB0q|ZWVrzQ8(BW9+Wx~6B9h&K&IRqCtn3Z! zWfDDyZB;*0FRl~CE>7>GRTFGgI*6om+hS5H3l`J;``}=HJXO`a&MiiF`}A~+EHv?P`(d8$E}kZT6bI+L-F$rO5k;7@)o51l>Zj ztKaldxw39Qga7k}Sal$Eo(*XVWaUClV3CHEpKo}X&_kSAYB<3@YG#M@gkIM(Iz86I z2w8lEyL;3(8`<{}gtPN+)QunVPuK)epjr5z9!Ir`1F8gHjJQAm(&#PLx zzj4Ze+vtjK3o4dNKE0S2NMS5ceY|32sz!J+b8+TPySo=;iV|&fJhqw=t=Qg4vZayIrft*a!q zVaV=IL+zgTBT{*f{$V9+eN0{aDk4@)cwnC6>Q}Az`6RmiE4zN&gncCvre>8)?BYqq z0xZX8`efuL>=xb<6FkOzIaSx%gkAC zMD*TAZ(M_G!iX$S&IXLIdoF74>~f3BOzFCGC-D1VZ(W}7lE3$IK`$do z)Es^Om2|BC4Q}jHV2$owKp|waAJ@t=5mIBR%byhkVNz zhjakHOZ~n$F*vW`7oW607wUKT#{qb^T2S@qP(-54S7z%-gD*op@#!@0Va~>u@=j=L zBw={CJlzS@>f<{M>wf96QpSxFsq4=Vbt$KEOHeb?0X`N6DHy;eyDU!iuKL%~j69KN(ovF%=JIWD&CA zzub7cSM|+Lb69AeyyIe$^Dxu$d-Fz~Ql|l-Kbueawc5?rv!k=%%gjwhLE~k*bE=5H zPC5ziCSJGhFzZpgqyt$0v~EZ^0ZDPHs_WYvH2%R_#3+Q;#->m1O`$8jni;~iORv3v zvZo*YyhGNbiKD5#*e12zU8c<`4RLt*?2phneByr9(Ho1ZZ_bBHalWJ<^X2EU(&BpY zvjgRh<(GUOfb4n>UQ-(qS}ogBy24f@C0eyt&WGZ?_`rVpRAU2L9*||iZDr~pd^z0r z_?#d@y}9_#=kknl^8@5)i$l-JL8?8LVss(A9j)!~OxaXusrJ_s?kqkpgWz8Ff=T*T zYruoNI1R8{McJIQb*^y`xQES(wrz+ZkONu5QB4{!p#V*Nqpt#*CC=|;z?&wohX&tH zo&7>M?q&y9idSfNvGoV@Elr=4(pRjClB&Lf8G93WN!@^{&G(>mb|HYIbV#PE6J>@YHmRH?GESGM z?AZagO|or=XRnSuJIcBIe`m9pco@bJtzDzJRb<737#u;$LLo1lP7`W&xkvfV7zS2&~XOI z_BaUA$7<@yQJbGQ8uOzWGG9>-z;+5c00w2ei_KM*({R+xeQC`yYhiYF$551hs1FXl zWz!3Cray_HGixy0Fm)v2>>@kW8G?g+56miHl1$$)TG+bZFjAb)PS{n4Wg!>H%;Uxg6&9s}5*`118Cm)xp$r>MN0f)0qV7HR54O1=?=cT#*7j0+R z?N^t_ynD6Jt}NE*qnK zw3RKo)3AA+YNl}&Up<|&5h{0StUByS27r+`EwCt3e$2?$B7wiWX52`0)zl9kbtpmIO=f)$tc}}L$kmz#V zbq+^}_z7V4OP7EoQPUu1L9^+dh;r`NJJ%E&WwLSXQWd&NrK^FF5*z zf*)?r)_@`=$NYsDwLD+Zy$n1g0L7r`@q31r>2)55)`E8PtJX`Vzvgz5#e!X3Gb>`( zT&deLe7e-?f_0@MLjI^pUB)6T*lY8_bejU>czCOQVvv26wg&};dJvi2{h{Zx6vBEWVr`kAY=zPdKgSghvI^0K+80k>D+9wbE zS4Lp9CeO)ruvhT&I>i4MN46gRe+;Sx)UQ?AGER4Y?Swo9oE*r2cP&v@r&jfr*uT~2 zd1lEp!5b{!x1rbuK1FK+^w5I4Mu89=n1-c;y{~u&HbHvRMhp)R(-oE3eDx)K(p05A zdN176_gw@gRu%`mJp{7S=apS|ZmE)jnVtJ@HHPe z;3(OODO2g1Dk`+XOg9@kQFOO+rzxx4GF$2&l;0ev)stnaLF(pv5zDj#=5vjd zVD4_VJS*+T#y2$yHK*>${XQ6viT8dCxNS^O@sV5V?WSSY?;B#AlQ_K7(8Rq=RBnC$ z7oH6pu5a8Fkp^D(rdzfNY_1F2+a8%Y8NQ#W%p9+SKINDxNN9Kl1v%C?KCJEX@u;ux z<_|UZ`UK_t7u?NxEwXEIP}qC_FeEJ`7Vx3#ZofxfcBe76Eb6h~k6Pj@ob)3Tw1TM> zAnT^?YV;JVxacUwUuMogE0ZjzjR-7V+Bm=CWy``K6Fahs*iI72$5_rEDtIy6-8D7 zb$y8d$A=e4=?f4dD7-;w#J_wbH*o*FojxkNJ8pVE8ZYP<(^#k6Q(+2uJd3MXNQ=Gc z&@B3CQ0@ksnq7`hu@^90tKWNCmg1^U%VTD^fM)zk^usUZr5~WE1#b0xnVwtNs$TQC z8!-$uolobp*L_>J+Ky@qQB#*^PO6SOO*`VM5dyh^3zwUgjJUtqC2j%Q4P`*=c=D6$ z*C>0aGAyvA$kXcpU)CD9*4Qcn9Wgwmbs8vSD`ArooZitfH;8HOKoxGt@}|t?RGbD# z9s9+jxjawLXRDa)a~M?>c-Iw-DC8#7*hDtxyUI^mPk!^O=AH}mKF#5+#`gUevGIZA zsG@q7)^K{pXUl69w-KoguCY|>KoEI@mnSdKv)O)g+;G#px4aCg!=)Vhr2ZpwuY=8I zLyydBn~%fgWo4J7!^54;mJ13xQyXVeGV80`|9Ka4n~~<7X8kp1=s%CLKmMrKIP^~g zzu+|98Q(GmTh_=>oyj>Px*afar6$|?>Jqr=zwbbU@;RjTo%L-W=ceUoT#fx!YWFS{ z`w8HcU{q+$P?sCJ9VK(CV$QzlWr`N}q8Pw(tyIB`vdPynhT%gW&>21+vNa+X^A8aMX$zI4vymQj^OTej*J-t(S$CuQe$!bfgi>aPI7<{9T3YeexY(|q1 zmmsgVabsN7@3PGvJ;cy<(8fKktBm-bc**11zu(Z31qUWv;P{O)d%My%gn^qR*(?GN00l0)*SUXW@d$3KTw0h`srN*ZDR|LB?dBZj~-T2weM=|>BQM++vR!7LEkb1 zYyUuOA9}E^B*(+iaK3?IEBDt-TQCKvpQtM@zz)qlrMk}maW*sh@gwTbpV0Hu5#^U? zd?S8oO)()D-`;RQ&zZ?ZueDc1X(BpdbVsfXss9-@!J?%h2D7I!4hW|A%OfTy=g*=!wU^l#s7&t$Ne(Wz?%MLBy0keHCaC$u z=;s{r`#8jx-^%XR&`ycb7-{!Uqzpfy<+)+@>Ld)~nJxjtndROaP}l`~83x}%T0`GWPNyzFuzD#e1JT*Tqdt{yT}`@1GO}0 zDSO~(a|l2);*B<^FK)}v;;C*_m29Qu)hMz`=6U|iBp=P3kgM|}{Gkh{LTC)V-_G^X zYto0^i7|~@z9U45tmCr|LxY;_g$CSkmLjnn2G?rMusG+rsXveVV~0*$m3M30;BRK!_Pm?T_S5|Xsi@Z;dsUZIT%g&ub~k-C_U@(;;6=>dwdtR6Q}v#r z#Yr4WZa=1i!v^_He?m;szBPqw(8u~bKZLE7Oa^gQUTjs_U2PKLGq80u)C>9p2opM; zM+E6dgp_XMGPyEp(e$?KM}NjsinG5-*)#B0CO6E=_5zSRoSX=x&Ys+>d0Suy!n`X!#wK^{1hHSGymC1p1$k}<=line zzw4bHwS7FaWp)>QS&l>PKPh8g8|jWPtW?S1c|N5bKMk=FV z+{Rl&#o+F{CkWD%*b0I`=CHSiX69VCCCP0BhLe(Tp zRo11aiwbsEcFN(d1ud4s;~jsxI7VrTxg?W2=1nHtbBgb$8hC&Yv-xQGrnbWLduS&C z(LgogaBi)sZOF`O@tKH~)sl#ekXtP?53|~vXHnpqg&j@8ce{-w?uSeqOa}*Jx-^8o z{;B4X_v>G`8+3#B9~>Q`F7jtzY(pA6=YFiq!%WStUJv@=LlQ9i`wt9E#p%?Bpzbt5 zZnHbsDclNstsaABgAmP4&%24$3tWck)i z3YSvBD1Z1u%JoTUwNxMOw_`w8cM1zLHD3UBPr8~czo?Q97_BviH$M18`M*26AHFn% za;KH-LFqY@&T6(8w5(Bkn}f^*%hI>u7a5SYsIzg`a*=^_Pr>)K=N_q=Z5Qea?=c1k zbkjp|P?>hn4~St*HG@r#VcgUV*pd}s(@7Voj@7&NdLkvOqMcwLYEy0}rUVP8nEWod zR_jdts!)a}#Xj^|%Sjb-d+A(+eK1C{Qbr8DKi#0dGW%=G;LdGeHOG3 z!V|dV0Kcje1e`lvJY!ubI_nq*_FOhM7tU;4H9B8cYt~w~70q)556QK$DcT`-;Kne*#33TWdu)AG76 zJRh10sU&ftn?>9@B$Su6S3`5CoX0HlVRR=n7e~EtWNQ6F-P?N7mbM&o5o`BjGD-MlZFql5HPEcAd+5x+3CcqP5UQHNNC0rv@Wa5c7{yoE43flm2KCi49peJ`-P!2oio`gFiSS@DxVP4kNy_oy<=bi**to$<;Gf#Y+W_p3%#w)Z>L|RYLf#^ zEd#e4k_%>?>O8-yt_f6H*GlymwS2!d8%H|j7j-Mt{qzU~3=cizD13hdp;uNlD@N0X zm&ur{DzlD?yA1XiFDOV->}m7yo6;@=uMDu0l|7v9j#I$Pbw$ryvV!uH%m1z#9! zns~c5;O|7_o7u2k(t|)VR2cULv%T9=TDt4P6tG8~i(Aw7GEd}m-t`Dx$r0XR@V1^k zPruv?3eaO~>1M?O2%j710O+-n<{P7PK4lE`ho|DM7S4!WO^Oe+Q5AvoOIZ8Fo932< zmxzs*@Hp3wLCe{JY5U{hbE}3;VRyKY;XuHItDA(VoB2~_r@qE7O26jEcI4!3ct_Jh zmR>M1u_G;&O1SawrN2TV_UFcA_UB$% zJH@*j(sCV5&TW>PC35vey=hx{(EI+iq8F8h($Po3-^Sk{5B9VYvm>d)F2T zXJEbQRiW=&jAi1Zrjt?lzJn+fmqclM#kW+KMudB>$jm5hoGsi+akJ8=DO`W^;ZErv zVf#ma%KB(M)t^iH&btPkMMdbX(orfO|EQ1f7Xa)1ppp$~6H60eF#Br6o79Vp6eI!c zrhgtC9mq4OAkN+NjJ7 zsfA5SujF-Vh4${Nb-i& z0(@J>zh@^KKlG}6Y)vS0F|`5Nhc|cKl4PGyh|BuKaT1geid&^*Y`z`@Q0$>2^fp=- z4;Rq5a~cO4_>kCDX`%JcKr6K(pXNj7T*^9f&T7pU$Ej##e(ov8TrH5t>Bx{xa#pR}?11pfn45c?ArPw&T=PqKz&pdsY=t z`O#PFU|ntP=^V^?u-y}F2v0n(Dzx2P_3SjGn>KjieR#}eOZEe+4mlp`Sp;bH9lvij zKmyf$ra19*RheF!@)7n*q5E+Xz)QWJ;9QYh=@@5h-fs~E9;J$K?CnQpzGm4#paR$UgL9_$9)q#k^CKTT;#z8;A+Q+)uf z26&(>O4jM4vfs#Y!T5EvNQ&pMeBd4jg!ysYi_n8w*!9@6Eb<0~hwEoWSk&ZZI5pmZ zasJ{#-ML3&$+G6I>Lu@$(KaQua;V-_^&rG(;7QhW-m0AT&s+f#v5y>ZKP+ePf3~@d zq(ilKo}W_`r-1|u8^*UFxpv}AxmwMZr@+bo4DNV_hpv!ozA(NH9VA8thYn6Lo}R7s z+p69J@3OU@tZ)infsClmsW<0$PLYu*-QWph1a7J{WTU|le5Vb1Zk9HB|W`fSd3HNNB%QK~v^< zX4L=w61`QgXx!0=-^x)`Y^ChJ%>#u(DR)}kpZMYo4Gno*k!MaXi6J<5PZ4`PJ$>lF zxN+z?#&0(9PVZs6Mwr-zO_lHTm-_1xr4GF3mz{R{)j;4NFpgNvrK9%1hyY5DwnG<+ z8!gmQ0W)_>XXu{Y^ZoqpVYx0cUxZlO(__!hR4KiExK@NWn{0=iM=ufqVj$)njJR4@$q^RfaPL_as zkGER8aekL%`H8>#>EQ^$){1jqz+?uX=!&kD@S4ESc$Kh1&HmFQz%-DnP6#eQWn@aZZkB z-w@MN_|<>cTdk@pq;(zY>bSz3>(@=y_o$0ut$2KHohi#(TljTO2_8xr6TZqNA|Jys z5ZM_-mhV|${mDSO*$Ze|R@*+!@3?7cS~Yf5U?M#^rv@Vggx3D>U~@LPm&@LorQmJ^^;8OA(PWd zLBl&~!br6B;5nO6?O9li9+8MXyK}4?|1Vk|`twvOm$xyO%~0t-O!_jZb45v2>F94N z_`oEtl=IFN$lPN-EN0%jSDC@J8TioTWhNZ~CT`bpjmgDy2o}{)-NMWcy#^cyD1kD5 zLQSW(+9tO`Vz%<5mjlMVt1FW}voQ^T+dCb?m#3cy?f~wJ0Gc0%e*kYMV<*GYa_YS& z6cM8>Tkq$Ep%}rqW<;5ZXtbVDZ_v>uDFX}0GPPB_`)>QoZ5Pdz%8SD?6Q>AqT9#sM zicGE#mXT_HH?u5D-=eRlyfs5QzoTomE?-Tv3AX8FJA5ahtUJ$l8o;Ua4{a=*<xYu>)$2R}2PD4@0%6EX-V4mzy5l#hgLRQa71#FC=@;J4K^LKg1+)Z(-& zV+adx$HMqLr#(sOmcarQo|V-hS>ag0M*VYWLzv@vY`N@aZXuOdA;7Clo2g0rUqLPc zs~yqVcNXA7CH3fy6{jI$a{o<<7%LXq(5?;x2sYwodA-=#>Dq{D1u~=vK*i!msbA~> zEJme9X5%8MN2eDfD906}nJjXkc-o(`Y$5r3N_7)rs#LNjZ71KpeO~0rEwkYXjeUDR zc>Y)`t&X0cSUwlM{;*!~tElT*eDvm$qwPw?N0=t4~(l@*41$W4RZ`=et2XyH-c7S7*nY=*v^p zG_lLKRkVOYE=I7|<>lS5u+OTzT}n-lhC5Ere~~YC`2&>ybuRjZ4xB3I;`fikrml{| zGU*6I{N*lXaPM4|Z_C7s2e8^@#D>bTZgA<)UgFZ7k%TPX(1(owu}l3c9xSaisrXm^ z`^)j?+-VK3R+ZVD-w8%lyb9-K2(68T8kLsC3+u&OeAkKr8AYJ6wCy3CRIGZN(a*;- z4NiwO-D&?K-W3CGj)Fc=SQV01SDm;t_@zH)HE*kFBtiZReRP3=ua%NB7+%X%RE)6M7`e_gy zh^p**s}tU)!q>D)M>+zhz{(85R?V3f|25Wzt-;*?o`kl#^j4`{GS`8qU(z#N)5HYz zh~?nGp-$jl!1uAbm{rf7#3`vp<@x!#w>huXo(|#j^KY3lI3!(DTgJ3em!3xU^42FA z_z1N65IAvsmmhA5=9vPqDwp6kiA7|(7Z$|_02ThdyK4Ru09$RQv@M*JY_Prq#n_fg z(LZd%^tGrIH9tfb{o4e(tS11PR!v5w!#s=+t^3GhALTxCbYj5PhuG&JQ;aA2W@@6Q3{Uct-1hu-=} zptt(R(A_CsW)`ZWmKC&p_SwiG=xSQE5a8)Nv7-iq0~9G!>EE>S$>kiS2eE>6rTTJc)cU%TMA9 zQyI)<^!&R~4`Q&5A5lFeCwABl;8E6r+$kfxr{u&DUe)enPVQ{wa$r{5H0grBqT8p# zswGh6_~~}S7Cf4ZQJ&|u5{u4FoY9j2o8^E+Vz*;1n?A+Kw~)OnryV8iW?Q)r#_7oz z@dXN=>fZdbM<(6g@R|%vosaF=J|&3#*)7`cyT=@$>3g>*-MpSP(ZYUWbU~CfJ;U^3 zv>5ix#rG@1Gj)Nv3#~=X_}0mek-=woTwa?0HrsUQ8q6Z4U7#>WDn#&_&&qZD8OUjt!!iEr3hAka2TrVaMcj0j5^S|H z+@a;tZ+$qq@rK_vzf8W2IrhicIuPO<=KzE>{R%5x=mFc5(ra1Uv4m!#-L54lH$I7O z4mW3F$NnC#lY7&@KRKK*2@qZa33etR;_k)Qx@>ui^6wu-0Jb;bqYB%VLGfiprWjt^TBVae?_7yScR` z?QB{Yhy_Rj6dU_Rc?j~G>1(JP=1hJFKg)T7o!I|l<1L(`0NZ!}4Hl3Tfdy%?Xi&Nr zl#r0_lxAV+&Rq~ukWlGHx|Z%*KtLLVrDKtl?v69>JLjC4^ZotiGxPih*WA}!_jNz4 zu&`Dw=x^1iA=Avn-3iz8dH=+t4T^0ew~mQDe3keOgW$1de~1@NrCmqqH%8TzEk;Py zu-sj>en&?|mst5mMA!*acqN0v28*!9=kG?(tu^16sZ()`@bb^uvhWFwJ}oAYAj0b* zGvvTMkioUCR2e6Jch?j|T{e;v+jT5jP#XzFo~Q(l9HPEsOp(tJo8O-MS-#2P4#?u! z)5VT5VLks$v(AVc1p|vczu2rqh0JB~@=1eRC3q`h{?Z_cae@G@=jH4{z}x(ry!Of< zXd&L+I?&}y>z;%b$Mgr%@4Ll;b43v9+pX=^ug;mopBYnu<@Sk1yVVTfL9k;P8IRDh zoqhFxKEp6FVisE?!JJYOLkj^&V5^X=wP>d(a<;3OS5ou~bxmm=HbxXUkI&7r+)>BH z_gQzel8G;{zp>|K56PpspNWoRu&{}i?qc9zC-tmS1_&9LaNrxVosF1Q1AkfR1ene_ z)cO@gMoTstu+jdGb|(;pyH~Dv46hGm2bWV}cHi_fu0>6(td3obzV+#I=Oy01JwE>! zUy#moy>GJoDQ1DT?Pjffm8L1}puTZ@?E=G+C*mPc!TPSP}JOy z`)en<4YgSjUJS_3?_CD3wrX&1UK2YLJM$kO#bcQi@_>IqDdgh;N$Xt#%o$0Se1@?0 z!+znpvYQ{SQh)JP<>U-}?%a7jiS;|67;r^scqliJts~dYdHX=6Rsmvz>XATlk|Dp* z^;ab{m9RaB2m*8+BV}o`BD*<8@lOld_n_qr<6EXSM9QJMVoamqo8`VI*%iJke${U2 zm-^4*U82m@V8A1D*uMO#_Z z2i1-px26V#jl@%*6%}i7V#{Y>#DJKSY&>W~9FdQOOXpVOdqqf#w=st%79{`R>tEC1 zzhcz7zt@CbR9;2tPUN#uXQ9z((uLOaY@J9}zz^htXDSo6^ON1SinMjVS=Jtjr?X5Y z=jPC?xUA_;2C5^ZIUg{o2F74a-ymV9HhAu!MI3u)7UA6o=DvT<# zk(!!aS~Dp3@Y{O0fOP()D>}aC-|drDX@;Teu4O9BOXZ+L>PB7UNjGm$BhawgU`SU8 zY+d<*he8FEW5E z(fq^&E3E-zN**El+id-thz=nCnbKX`^^!Qzg!qJ@-!0_<3pnJZK)c0H4;n3dK(*HQKm=303X?Nik z+9wimiWG({zo%zs>7cwu7N_PfiLv307QkhAbtoDho9Etm)mk7>N-L!hsGf5pOKO@C z9t5u9&9CDajTb9&x-Ye~t~Ip0HG(&$u&DjP=0b#A0Hb_kCfY6Xfy6RC`i)k@mP*%a`RyNeYmN^^LR)p`^kQkU9Lm9N{0_D- z7reF`yff&#%g9sr56L~^IOf`uB$lSFOXv;{saA7d613%ooi4KhAN86Lv0&jLF%B=` zNWwKIlQxFU4ONO8u?rs*9OL~ej;o3?`ulG0ABm9nX2VySopnwt19GG_GqlXyTJ6?! z{YhQ7)6Cy|L?WBiWTmd9?}Qu40746-6={rM{+2G;yWU~E3iB(qZP<{vb?+G7 z65Oej7hL4tD6VuZS^c@G2xjpz;%n!7qTE@Ut!NEXBY#KV(SY*toW@IIFO@l!_t-|J`UD%|h02w5P7gxX%I+Iq$yCnUFiZWSX@TR3wN-;S<{x%r?9 zVOj~g`u*eBC_Zu=t!_gZq8P%}fJY)9c2ii2tRJ8go*g-=u0ua@9@`Rp%ZTs(1j!im zip_+h#6*i}Se?WQ8M8fKWgRM0`ma}_=Osq*uq(PDKVJjE#V<1X^7+d{ut@S>ugQ%p z%FJNXQ0$WmnLZLei|0E+9gr#%y50|?2H!Z_mQn@S&(eC`KG)mDEuz4sKqUh4WNF@ z0pS}Zk6fkbc01o&SXPj}ioSi%+H^HRv^v{Ja%Rn>L-u50FC_pX<(>{x0WkLF1?v|A zlB~Xg0OYZ@kqlLIbzBL6hfNkbjb&GjwdEYd&jk%>pAaumu%i_4f-6IMCcRbeU+B<# z%O;Ha=gMZLXzwLc*H9HV@gP}ov2}593D6@03{3n5N!A{}i_~i&h6FBCxO#wx#WTn4 zc_+B(Ri9&e(GnL+D?vSu5|+nfcRb-3?8!u@+%rws7;B04&t}GQdycm z?vLFu5Zf@FP)`}5+q#74k@PyPzaA1>$qt_V>Y=WMsh5upT2Nh0mZ8rZ7HWGQ5I@t$ z!-P82F-!zG@$Pe&5L}>t;m=l&hPqd&W7fGPdyO%jWNtlhwiOcdKgI@gIgjvJZO_iX z+V6CjP;e3Zul-0j5>=+xc+MYG;;=P@o^>Gi-!)^pL11QgdIM1e?nTTaE10hGuDM~+ zmkFewI{5{A_vCL&uG$NOi-4s8u7FZRjkHFc<>v6eUReun-u0hH%W`k z(b(G!!NvyDDmxE5k9)^h91T0KrfKeZvH*FmFUt^E&4Vck zALA_gTlM!3%YgLCqf(d4wep7yK3qGqjV9(!$tX&Ap+%PwC%rXSh6eQgUh?l!SBMeb zE2PIn8=hZOGztC0a-$}YL6V(z&UWi9i`ttv)mz~6wXz(I2B0u0M+{jiN6b2l1SD{_Uu&r0JPqv_WJdB44FnNO#&bI`vH#ie1f<9rV1jDQc5>u&N+}#}- zw)f0Fk`;Lt#1H?-mN^Zv2Uqj}z7Nlg&v9=r*O6eFh$?DY`eCXWQ0qr(0$;i!fE?z| zQ#VH|$s0AFmRnCjzIRwc2nP#CG0XM!wY78W9Kv#=<*`Kj@nF5ALJecvFFR@!X3Lo? ze29$hGn>A?dJV5Yjlid^CgZ}=G9powIg88qcW7T-fvlyn7OjB*gWKG8*T1|Cc6@+w zhhm4UxtR{S|L^G3RJj}|zK#t!JKELtRCk*u{*^DD@h={~@fScI#1hwZjEP4&fRB%R zk^moo_75;=*w_<)o%NDMv2>`(m}qFQO}O|y$>P5>E)M{nQIuH;`?k^tHz|wES@Shgx^e&&PtzgWOZ}mmrK; zhBtO9I7W8_xnzO5kTsA?rJGd(J}25A%4&~QJ^YxK zWrERKC(IJL6@7u}r?oV)u#!Kz>btNq1twKL1o#jW3Qd<)l00J?pXR}y<}?V~0<^1V z8Alm)x*5p2?<=4s(}!5z3F;VPmBBr6Er;p~JnY3sXlv4IhJ#4bnhe`-s5N}ipJ(n- z#{8$@s8KFFoLC?6{KI}uD{r*#9~#Pr+8S}DID=L*D2K~Ji)oP@d!QQ^%gE4siO}{m z5}0H|y|{Lp+qX4PZ7>k?G^D+&7$`AWaMj*VIq`SpX#{WG)XGk{;KhkVrQ4eQGI+|A z-t;&{&%nR!B9AwG+xbF&^LyD9MbvSa(0=Y&?p^A}wL||g<;5jS)VRR=aS;=r%(?Lf zm6g{~0|GoT#}ctXb2Fn@CU(&OgqR&vO^qQgvQ{%S;^^n>np?V)?)pT!ts*!xzEV7{ ziyeVzCV|KtOp4}^oB$fCaNRe0n4e1h3;I)2Tlt{A*XqQ-fZwzJLP~!gS(^cf4W=#-V~&qW;8%aL>w6aH{;glhRAyAxYQtz~arh1YIZRlr{5#u1BtyMRDV617K- z5rhPYqK9Om+C4o_&uR(8|Lvj4LbZ3uzZRD`oQUPKA)^|^kYcBCT3t^am|s)7H%bfW6SD%<%GBZPg&6 zIR23?U!^&hfRiDeAxDCds!f(j@)fDhTCDb_q~T{ImLG1I#iZL$U3H63XCX-TtoO)k zJ3-YDQ}HWq&Ht2c%k${VRVM<0n3RS!Ht)45-v&D`ZcR}w`RSX&rQ!PE6PqFdRK4LK zEOUQotLx{@&fZo{+E?Gr({GTxJ~J(layC~iA@-$r3lvRN)!3;X7?$-R)Ugoa+p7*F z&jLXKJw$%fWm&)u8FlCVTv$yUM*qFP$&8%MtO4A{)!tvVb;mz+)L*b)PntrF5xXNj(k{Chs z5ZZX|bu2Jqkhu? zxLPxjnS0pPm!&{-woSP)c(4ew{EEo7WTN!WT%+TcNF~8~v&D2z>pF9FTyGKV`t?ZV zL(KM>#p7MUQB?1*B;yYhAkQGxHPQ-btj%IcB32@6%Hf^z;ehc2k&&yk?Wjm%V`{GM z2J{z1rPzk?3H=^nccQXP+K<{6WO-3ADIliMt7hselkGPQpOPz}f(pAza2y`)J-PBv zt(|55VvN4Co5n2Hk~}Qq%-=7U@c$2nNJ1*@DMer!cSim7(-}spw$;3L zEeTDj=~nXQf8ToE(2?6qp#n$G1DwBq6 za;94DsZ?#^q_at_rDx^3*Nu}(s4g)BDNFa;-%rU?IA&0s0IjnYO)^k{D8a}Fin*81 z`6j!Ng~XYc#=u2j(G|m$93caW_uAv!^7v*q%Jlq&wxW8^*3SNX3fsl4q^WQ92)vT{q_@_(%gTf)jQlXMl!CRcD-Sh z?bhC_zff>UR)16n;qpA$NUj$GY9U*tPayS6?!g0mtE=S3JlZ5o!V98Hs}4A9VXbex zlcU)q7PMW*^UixnebEh?ok+(>ZUIs|wb=9yyp@DTA;koajS;1Ky`Uhmok`Gx?u;N< z>%axxi}yRJggV8c>Ej?0nDdmPZ4%p~SnNJNsw}vroYu+Tn;o=ESDy}Q&N0r6u>~jQ z*PWgnf1Vs*tCkFM%3*ZC4cEBa%+ok9SgZ`+bWB^hLi$bh-iy~jM)io!z{~%Xx#IgE zj?1ds#1d1Uul6f~wFh4dA(~aX$&(=Ky1Kgb4I2!Da$HO;lv5xvext;80ewO>ws%ip`I+#s@W}LFL|R^VkWdzXE(-Nykjx1MtXl zFFhsYsuxw*eJoud99KFjOLcl4tKA-|2_VoOztmr*2CswOY69k_)=v~E{$KPzQ(Sne1He-mzRT{~{8in! zca`SyYTk+Le*qW_EhZ9Z3?wa?Dp~@v6uO}-0lcuJqL-c|83fb7*M+x{Wt{5xg@18_ zWlEKDatjY8KP8hN=AY)#~f_U;8^` zO&HjwbF$^8Ka zory)&f0hXG9(dVhNv~Rc*cV!kbj;u@abqdF8ju(19d%u?pbW*>T<`Xq>m9u&S9($^ z8txk{8seUsCrGR!z$+kBw`KcKs!V-fuJyL_QVj|H~WsEEYX2={2ZgQ1y%UDv{gt zzu%6YM1>a${5LHB6Y$^RWR>vk-|?TryOvENT$v`IeJ%H{#gGeg{g=kM=5KZSev0s=MDH;@Kywk*4xMJ3-oNP2t=Zur;Zzu=aZEI+VsBvF(IL87 zbLce;)M5V!aTE>m_KvxAR9{MY-Y6rEErj0SZE_nl33$|bPYbPBuH=KBmlqNH&mp8q z=IWjM;GIg0#ZndB_+l@KN!24mUgd-=K=}aoCv-xXe6r`6Mf46z8vB$Mxa(#yC`{R? z^o*PMWg$P}w(K~ot$fPIuWid#xDZ`dC;X5rY=bH2CkTooE~X?kU&vXaVdruEO7Ya( z>RXmS5NA?p_KeoRxcJr6JYI~O+H!`vi78{mdBUf$y|D@h6Mr`P!Q|G8mlfzoL4~gW z`fa#faCBdO6zv7R3gM=bDNF4}rPCICeNY{cA5?A1%=iuAuS@%F4AtJ$Qq(bV21e4EL0?`)H7G;(P6o`~fW_znQNR2WP`Mi5#zD6X|&PsU(yU^ux$Aq<{LGf;Xz^N}iiz%v}uHYpnsQ#A9(s z7)QzkR~JAFds%0lLLO>uMg5@3_~B24cWowNep*v`Uw75chJ*x#i-#|8w5ZhvYusB< z@|^BxxWez7K+}UO8;7?=vX(0`_ZMZ$3wrlzSOGL?iQW?P;`NY2-c@aQbt9yNI{f?t>xmX43ID~wNq~-g!B|np9n66rWZS+(T^mbP(-4t%_ z#(;~)c26*vmQ88&S)BKK;C}|DRPyeh11JH!2vDv|z-+`3xyYbAlB(2?Il#_ynmaZU z&I>aC{#4JTSNv0YIDvV|``C)6rb(*dnr|yRv$f;!9kH~t**sD97oMcpGq!HKnJ*7R0@OzwpnggB++1fMV9J3$`US zKKd=_04k>Np!45}Xm#M8COiVQ0^xs*8}H&jR&7uNE%k?Ld@o9g~vi?G)-5GlaT zfG%|KRTUV$MB*^CF8QCs8NFnRba7Yta}1x@=d=2N_=S$xb%7A zuY{Q)tDLj$%M^q}41*Hr7BFOb?x}Xx!WHc~FINz*e&3Q-n!JF|h^eRf9Zp&UZ>6h` zdn8ic8Q;m|Vh5cEwdc3dm_hEo?W2(%Jq?1>vr)&xhiqod?>44`HxJP-K>5J zcN0qjmmAxk!^bfIrPA*PH8Luw;Z<(HJWD%!Dx(dh*+k(WC7Tzpfg)OuWBnwu`^}VI zNy>a+Rg$orCw^dMSjJnqG9Ui^thxeHwu1+f!=S&IkzuU2Oa0V6;}%`qmAAmx zlj8Rt?En|kCupw$rum)B%1s+O(U6hwLDYWml7FYs{U$lL&C=blcUQP{K%joLSDDFv zWg73FL#+UpJOg6JYw|qqy=UD%?_<{AMS5&V~&cb9?!IwE@3PyO?LIo5t*s zZicJZbR8m6hDU5NdYZbC?!|;ARs8Woi5AyI zsX;9wGR>U8V?;4*aw;G*jjniCYp*uehF`xOeywtAq{|)4<88YI+-Lv6>Y>1sW^h9i zNu98O{9}5`@9Gd&=3b9PXd4PmOoc}eN2@>gx1-8r><4cFa#YH6Z;b#?Mezifs3fFM zC&sy$rr&|jgb<5VPVKh}`0}Vk{DA7&>Mb9mhKDj0?0)~GL-+OH5IfnP^{hVc1;21} z>iHD&m^CX&5ckiExz4!5fTmWHbtu8dQ$NOe2r$>mj3_W@1rhcgeibi`Y9?*Vxl9m*;djrBgostn<6 zwqy9cfI;~rhWo3Q8E{&9Tz%B&?B2+zt?Pf1)v{GbIJ?wX&@$)VCc!aW7J9C z{L=A-k0XXfa6p$rSb_l1NCS3=j=JxxO1E0At{nZ>lnHmqxeN0m1UK^ zhuc((k&dUiMcI0O%6^USn%iXUuk8zaw)q`M+3|Fi0045-$njoi63kYsHMK?iY{dA< z;GUq2^d9GY=Ms*c7@aOn!6@(0!ZyO0j1ivx3mJL|ZB0_Q&i}`#ZMdUgF+r(D-`^Et-zlpr#IW^=F&eTbL^|Mfl43 zHe79;e~K^2{u8tC|5?g0YBeSlO0)y7CY-G(1Ou;n~Rx44|9x{h< zSTGM8H=*FEW`rJ88Djk6!iZi8uDxF`Z?4T!>ZRZ=Qg&m!O|Vr0I-YkkAlltZi(3GL zE;MiYCzAuVA5q~Cuhp<+8J2@XQ6Ulvt+sI;H_=3t(=&794*dpMOM45=os8Z$(}*x? zEdmVLe#;Wlm&@?rhM%@vD)#Kpto3Qx%zJ5IO#Y^}X}9rT!MYClG|Qf*suSRd|H9mZ z?g!5+IK`Cv@t`Hv>;Z-vg~kR<5$;HNkDQF~SIn1<-Y(9Y!H#S@4tjfJ59Ff_R!Y-< z0aylTt%2d84g}d>Kft&+tStt%ZJeVGh3E;sl863`02Ui+w}yhjb!A;T^$Pe0uY2?# z{$-iTE@6+u;^V|B-2o0yj<%t=wP~(8zDUPiVVUMCk@1%`s9P5@+CPnmbUb3g*XCwF z{pNLp4Fk8;p~}|LyQfKvR58;Hwi*xIAHVt57$F)H@Em#)W)d?yD0N!=+%*3Zbxm1|qdu2x4dv;{r-4G{|0D{uF_ja40#@J9eU3z<*>tzIWK$goPA-v5eauHMd z7lXEU>;XqwnF;Z2JxW1~M~8uf>oF&n&$@-z^ytj~UHf0%Wwf>58wT8`c`{44-WQzT zpWFo>wce{u0p4>;|LKpZIa-;rUQ=iq7Ff!=KoPY248+!aXAM~o zkV%|R7Boef2yh?8X!W&O3rRi#OU)sq6?jQWvb>=cb?q>tFqT(*pv@|o;$OW}WrEY< zlprvcj?PF{uNN&*2)5ACc^AgPxw)P&sa{5x0m#4JYc>MdPnQ|;7wU0~+o8i82oAFJ zb9Il{Ifto`r9z*gY5ou#h( z%>Q^#L1VvvdCUErOBM%+rPZX<@VPlq!Gu#uSqt0E?Mo?&Ny)am3%0AOD|8K*FHsMa z=%b3OI+FX4tR4P5KE&D@@gvhWzjg;znZSiDQoWp^JK-v>`At|62hPsc3#)5U{*!#l)b z3m&YPxeI7UCYtKYl}6W2%kCp%_3U!yg^ss7#Ez+$i3AmOJik# z>kshk%C@d&n#dL~Va|JNP_$7Tp9s;M>X)L&hzk}+(oZ^sPQThtN=}J$;Lj_X{Uu7G zUh-w^Z2Ac=^jAj31THF4kYw@a>Xc}s&`wpQzb(aQieoPPuLehR@L-3XD)UeWZ+)fG zg~=3AE1PsvG@}UpioKEzcrT=FW*%9b_(~D|L;MCW>k+3G*|@D3&*2$et06;YEojPs z?dL9O1>MIp%eQQdmdkUEZj+A5d8Iblz$p}KvP0G+|JJ&Gcv4G6O502d+1Z+3PBC3r zqv(^03l@5?&1u<+QPk3)*PKqrM2hZLes9QCGTmCMtuyI!ZqQK`QvOysef>jGa1l^K zi4+&qVb<}X1XxNpmJiTv&UXMX-)@iq4iualq|)4nIoLO^J73D3WbE+WPL0WVzx-q zQ_QJelx)FW%v99J5l>rdi(*HLI_dylXdr%{!Dh3wf#CKQeC;phgjtmBEKSeLU=?*h zA@?9IE!EbSI?SHJzUGHpd;{5JLd9$`Ky7_d=eednWL#^a%~xue7H_w6uhWb~s$o5B zawI-mV??mN#vqlBF6E7yb7I`Dm=q#`PAwKvb-OFnA6M3iA|}2{OYxFd4#?5krhHty z=J=DWP!BDCn}cUg^w>7jb`QE8v4hjl$Bz9$nPY_81#1Iyoojl=A9@34i>n9MX>prg zHKw-IKK3{hiQQu9_F1ax-rd`7syZ@M5y4=)oF<5-=mp>VU#f_qY(oy5x)}9r0?z}; zTJb4|po^-dDq9h@GqjcR!{wRI2m529HRJ{ztXRL7tyf6@Fz?0dz?t&QRa*0?>4_5P zYu_5gwJx|7X?6v^AQt&0n{rd**KqY<-p^{NYq^79-?Jx~6t9Fd9pwRievo1yG1p0O z+RUw)bT_}w=c)wVs$vn+->m!HrDAeZDOv@wWBEA@%2YyVzfx-;X<<@6C+E*}lqEUc+Z(o_8Hg*t?VYOb21(IN8f-+m8;O}--MP;%W@_H$A6`EjO0>UI z+9&vT%NNL`m}&NBBk|;N4Rc*zgzsV~>hEH3-LYf(=h(j6^Zz=#{|*_~6oU6Q5WWLQ z5=fuD{CC*#u&8iNO0v~5&{CN&{FH?XcnPvdU&^M{fV3b7fka7EzR}>$Qa3s`4Ds@R{Tz!9H-p- z#+pEJxh0<@e*s|Mv2wc2Og>kSc+J89?Db~)rsrn*z|m_oq&=@60>u5T`Z?OvAUGi?_^C2vOnqFPu|E&MQ^rH8 zS~g@TSb9djLtJof_OO_9i-ZMqZaEA%M|Ko4e_6#Lr()4%GBev}Qy(9jkML$(hv~LA z8Dq+`D`g%!4^scq{6cne9&WaHT0Qzi`LF>8^s!CZCE4n3VetlTPg*`kLRy;sdX>ZX z-&=Y0!WP-FR7*)f-|)&H3GPqoHX`#U5HM`TSVvWNWtw{a#w(Q9jMM*cGXQC=~my(jK0m+e3 zwO>uL_dWd<`VAu`@dOPp%f!sc`H*pg9rYbbtxtGUTP}uh_(X+`oQWd~bIE$)q~PZ$ zI>SKAKoxO)l`Pjj<8Ip379l;mmQ=W56ke&tsZ>#&+yEl9rZAHOWvM~6kg@x&=km+?+mnmor~i)4BFaoBAvA(PLa@mStnF zfQiQ=;%cKsvxrQ{mk3DymCiQQT-!t|QEyG&-*BQ0ql=`0;kmr#vEGYgA$5T&_8u07 z_rC(@3JD;dFg)1yDNW)zKfdIUryxSUTpwZ5B6tLo;B=JkoF3-a9#5P*Gt2E9i#R%~Mkkw}RF!~PX9c@x9M?|^$;yeu^&7gN z4c_FiQh)v>r5_9?@@8Y6!9Rc#8G@rhvtnw#zIifpg{2V9^DZQ6WO z8x%eBA7{jJpwUQLS`{-7Z|~WLCsJs1g6gYC7>OYz{XAaoaNZ)CT@Tool1k-2J0bz7 zSrgS7-j*)^Ht1?4Snlq!P(w31U{@8?4~=hF6Wdy?;^Qk6RcXY`clZt{^>eEYHYHnb zdu!hS%s(ZgmP?uK!S^B==?dk%-^T&POB`!M70~)=3mV78>JA5D8N8S;1tm3=0D?hs zBYz7fx#!ge!VbY#AT~8AimBylaaozUHojTONBDUFFZ#`FzS$M%=*k3uDTQR^X+P@0 z(9G3_C$=CRFWNk5*g*@opLsvi+$p|zD70ps48)zAxg+$O&&GUrGli7?w`>TP!BZx- znT?shbE-=?TaJrMGJd1gW~FM{%gS~e>Q_$7g99(h^xCgtr(XR$-`EelCsFH%8wNxIW1KmbXu}p+kWn^w*EwIvyv>KUO4b-d=j1WSTC_{QxZM}FN737uA+614#~Bl29DMsA%0SFF0`r3cWdIQAU#-4=O;G#fUAaOSX1?l* zDwB$N>TB*z(ty{KsQ<(o7yqp_j$e0uYmt5nxRE!2N#|{lqcY&^#zo$da_q63AzVCz z9!?=p%bYjM1~gK0ERbBV$fNkEvDeU&H9~vQPX_&lLu!dNLKDItrBK)hMchTeudnNs zh~7H=Zjg-@%V6VfT`Vx_@srfm>Id23<-f%Hu5o6tpnq!{(LeZy76als6w8^QU`pU9 zO>6wgB`^`st_uk{vixxDg~|$4_OM)6)#P_39;#AatgL=2akly9!*LzD!oN4# zWq5p;lt%KJwPg8=s=>#`+mil-}t5PmNQbjX}~E4xRU?_~i+ z%~@G!Du_Rx_|-tN+t9i~OOl#|QxC|-Rg0b=1h|LLT4wZADQnj{57f0=MDk+ zHoc{Y$6%OoXe9t~yD>V2LL1O%9Sc?)_7M5KT`4Ikd9(ZHqTek#GeF8Zjf#JdglS7; z1`cs6$w&8H#oWC4GU%Rvhix}XjI#;LTK(sHqu|-9|s#bI9%We?qA<5ZkswZ-e8TKNSSXp zmp*YD)vxYTG7cPHH;8&oB}QldO+Dg_Dz_92e%;PMh+I)&?2OP-BgJB|%N+zvzefr# zslWQ+0|Kx*`zcd5ccb9*xmUyOxW{c-eEtlGprtFU(Zn$I^3O;fG4xW*=Q;7E%V?M0 zUFm_vnf!7#BkRYr(E6}=PQ6cvxw`Q4*7LySm(s1fALp4{_nI8KN=#3S4;Z>Pi~R0C zObs(e6ev}vJv&bXR(>syQwGj z6%Oo)=6AniiI!mguouw7+`9rqN*nyWw;GZ@{<2h=);@k2b8{@C2^jGaS8LDzAAK^e zQbGwGY7D-jm7cMV0XNnt3`uZ6m}Rn>x1a2~FQ3Hft!bdmY^3kl@wVr|AW4EZriu$*e zON+F+acPKCWC?^D)t+O(3|dgnulM$_dnKE`hIdddFRaxE!APlB%fgNPLVf(&;%q02 zrI?T(LqkJ9+LM=_qV_NCjl8Y$B&h*rhexK6AYDZrcN0M^Y@S{@?H@8zz zv{bTWpwjVz?aPq7U%NuY&ZNWhFa`1V2IILNKb(9jxrg@)Tb5jD?4|SCq@$BM`a|t^c1^^#rnfOF;vToJhm|je^#MH1RktQ2C0v~vOH^9r0k~vgm9`@k-T$`{03h6s0=xl2` z!yuQnk(P!$_XTh)Me4dd; z0+L2*!u_&(ZVtkwpB2_~-Q4Zpe`rvBc;O>$=YWUly`EQ_ykrFgRYiN(^gh}5kNrYp{WCvLB_<|DI?enKTzmdf+q9rPm?hwHz)T8O+bj*p7&(kNGu&{Gu2GG^97e!o z&`r_K@iP%OK645M8}wU)8!Jnd*8fhaGUJ#DqJIcTNr3+E!9&HpMC^aAgQPmn!!s8S z$L)zXA!m1>XQKXCUwqNM*7HPsntnV*6cMKEQAzVZ_yD0#QKfxd!ME3P4;eagfLqS#a7pwGob?GZuB4=Vw50&! zg%SM*4MGS(gX(i~&4z|fNO>2C4j&N)E;I9CMqWJB9ngFFcu+R^U6gt)rC_?zYIG5~ zaCj6wv#|Nv!)az%nxBDm4u=4zel3u8Tzx5*9$1!Lhh7{eXz^S9MgZn`ANTDS1zQ58 zeqI>`-qo}c#g`;EtWYBe=1=^%gRV}JazK%@bNb2 zO1hY4On4Uq{R-3JKPiVIpxaAnj=dTckFJZ0l|t3?x18+jQpNI#pbRh0=X+=yL_ZLj z%ZdvKI0owQx~T92BN(Qh90Zd6upNAEW0b}o1k5X3=@SS06>gB46S2%nIsKR)U--uT z85XEKWL(d2mge1!M%fQAZynjx%}fgt->lbcf<%&n3zzY4t1j6m7x0lOtOn#%O?9vk zzZx6t-o~lef)ipV63TF9xTJ0-Z1ju5;ZbT6Rf!!t5;!U_p^cv99VV{H+y(r;5vUdL zIHe4jbXK1;EtEi~NacjnoG@YC83*6eS+5$OLJw>Qz zjIFaUAwblLY@f;*kXmU8TMi5{N^~ zIhOy3#h>#mwqsO{{Twr+Sn`F*3<|rD1zPMWS)`UNc%o>*U;k|=MV;Gvgk?K*n9ab* zJ;@#bh(YH{ka=E61sq@rY_-+Cf8mk-W0mni+=5zihJN(F^U%nQ;~kfkC}vU`sg=h< zdv|w~_u@B8_tztrVUPb^8#J}Y@9hsY?E9wm+R_E9l^uEmat+Owq<- zrrXE^aNvAE1_Vj&8iX+o4mNAJiAZETzkccqxJlb!7(ZXKd>jnMAR=j0uKUE9ssRTS zt4pOV>4%q_d(Hb~&0hONw&}jQ7h~kXREwAB$I$I#5vgnE#hSjJU-fOLsz4llzI1`Z zy-Bl|5-{M0wDicOG&$1jya_^i|7-tIdz$mzIsq(U{~b_5@_Fu(Cf@%GR38ue9Ym|B z{xo$(OE--vBTLI61h6oAM<#1t1|8kN$w*_mvbq#!NM*C5YHWMY_c_1k_n!BUxUX}c`}*A1rMNcL%mprtojPpvv3Nq8#v&LV z6`DndQfA6)R=+5LGk(+?8xFar{N_EdVbDs{)c~rv{q9o^G#6z=G36A#MVUL|UyU#l z*AOg6`@$I$7XMnjqAfR$>PZ)Kf50#+{}NTV@pLmU8Y?e zawV$C*FRlsq@tV7>U?*=m1-yWPw~;5F~>Ycw&Gf--!qvpzf1qg@^uUlZCmwuNc}ostE)x{lAQ2iI{Ask?dX)W|L6D<(*?!?7rBgV_8<54- z04%A(^C|a$7eZCm%d=O^kD;2ut8j<%b0Pnwx$}xfkco1bgb*}+Bp+#1Jy zNi@Yt94=Z7~tRRED>uDpbgq1F;+m*&9ui-hyZRRxFHT> z&wI|m_d7h@#JB^2ZaRkwa%sO~Qt{=}+S6??`eR6LH%Yqpvtso`fP^Vmvv40~wHRQ%R?R+4KX-pvP+&5CfwO71HyQY*ko5np=up#^%8T_+CV zzuEt{+!A$g3T^6;y+1~*asuuv3jiVKZE{R!T+E?i++2|SWZnDMsn{$F?H@3bhlXGJ z)A9C^M}4Zki7$HDd)eFQl6DeAz&+F-9IjA0lFUcRcC_dI&ryrmmIoMxd!j3!Ox*#!6ESc$UN1v9J;2^?8+yuON8xw0! zR7Tbc>if9L4Hp(CpN@eRh1J%jIZ-Z!3VAd1GoD%pcse%>56A#-22Jx@%Z{1a?5Hy9 z$6pnRyu}oQ059A;4_pBaIi20{)c%czKgje2`=Nh&@RaUdQSTZl;`}Cfn$t^37HEFU zl$cZjp5(AmjYZTwdO!{!yp*ZiQB<7ZqYVG1MN{@zku#}tnl%37M=NVxTh-4x>c$m* zjt&ln4o0w$N>j!3WS)CdR*f2QJhnW^g4Vx$uEWBpVz?lwBHLFCbWByIL`8LFO$HFp z^S6;=sT1eA>lD-k6e}#f*7=NNrn0pYn8Ai6V%qeIeOWI{R!o~*g?$PcQ~p*lr88B; z0pVm6zQ?*jNX$%i-Ju2RMfd^sS5eQH9vsh2ISk%gc+X4jS{MF~gz;k$0i^uR2Ms|Z zu?cFQy2z@0qDwuaTFkPR{>!$Lj000=@Y-|k2@B(pCk}wmrMwgSh6TrJ^y_?N}85`@VlgCv)ig{%z;!-x2@HL zMVV_(f?F$wLrgIBjG;0Y1pLO6q|KL}r@!{dO4aOJ)I!|U&QYL^t7}zgUt*gC1?`WS zGb6^X->iL%+5T;>X@`%w8S*b9W&pE=HjN{{nUgvK8)?i0Qvz0}Yo|GA%#^>6+>&oN z_1&B&qkbBnD{t0!^J9EhNwwP}LrDuj8ve}pTb>N=% zyR6pTzVk^1*6n!xDD49_-XB9&b0s?*$Smsq9Vi(0k2+E0v%Xq&v6Xc>6R7QcneZ}n zch;af&Fqcq7X=S<#XVV&3hfasdH8W1m zdr+Fix4rk|`&^+w;7{HJ@ZHy)rD6UK-eun8HU>jGUUb)xxY`IVQfFbs^@ zCMP@%Mrdl)T3}ADzg7ot^AOA8{z2WVFr`3p+F*?$K$d$@_TKgAvr+`OECkGkW;wd^ zQ*EKAhWFQjcNuWt>|8(y+u0{viCK0FSno8Cw{!C za=oKW9F&j**9OX5+;Bol`P5w3Zm-6%q-(FdI#i@rC$Ul4)w@gCuoKKK>6(8%dq|8r zSQ8Ou6vuTUqiK~U(E!BI>N1{y8wmU zF8L_&iKx~bg@Vt-6nen1iFXjrW6TWb`l~Nc0mrs;2COr%n{CD5Maj%lHRjKao0nmR zyU*>4-@BrX=9?We71^!|K>)FEHHbwc)sJ`N^yw+{qxfTqPZW*}gO2mnX!Zw|FFX@g zSjkSDSI-*MlK0n0QSKd18&yaX>d2QvpTbuJ=7k>xNqtU0Pi6P~k-Q2ieW>{ys@%W#wYE{QVpl+)ZOm`)~wM8&@-* zwy^uu>k%#4fCwQnwuv{XCYG3Y5cFIrZRTs7R!Rh3k%6-HM2I;Lh=#tUnl&NYUqZ^UE@ryL473%vlC$C4=9YJ+%|+|lGZ!?U zw*Qgs|N}ss`s5N!<4qbdTSog_uhFV71GoAHJwK`SM{?pB|;}1Mn-u*f3 zmtx))#;iAf{r;#Hm@~z^7~zb^Ow7!pctWn_J@R>F#B)zYLHfeJ_KN*P4r;6=T-8#b zar`T9ndYE5?6))BjJKzD{OEgok~loN@?#LR*?MC%Hz3gw` ze0S=Hco7o@81cl)dv0ddUX1y*^WEQOcMSLa%k*2NUcJUTcOT4@YtEzh!~Woc#pLX> zEjQMut|Kl%&q0B2|N z{qAXX)ah9HYt^Nr?tu|Z^`vuk(28^SP%_WOXhF(;LdXlAWxr1Ev0JI?g4nA*?-2)1 zE6b}oo}*^-%uJIUqsr@~?CRgq-%3SZnr3Rf2Er}in%B-b{9;-ayy_xc^j~uj<|pK+1YjYnz%o$5HPlwSPcyR zy*WBEE;%!HF>oz{kZ;^UTc%=%cp&T~n(`p!&(TWJN<-lyl#?<){(ociRS5IVYiO0{<`!WKSa-R#_!gvU@^qQWY{%->Kyu0S)Uz8ftA&O0%-RWS` z=@`F6;HFSxMA_vB6M;BSwZ|dg= z)jZ_j&Klfzn+ru*|Ap18Kl=a@b0doEV|#*`*P` zMIBqU(b&@bq{G-YmH+8V)(x&VJBum$^{~Sg!%SRer8$LlZ&~Vpuc|plYLQj($JYJv zl;${yf_vhf?R?S_KryL;dMK^+F0#hEKfcBoYHzRTvK9m!tu{tH;Q@GrCc%|;#2E}IxeMGP6s7-p!#U=*Vi)@2`kEZexd9XB^>Uj<07OG zhJUY<;8q33bIv+DGrTr+)I(7k1Iw46ZZ6KV9Bw>_qci3F4vc5aIu0!hXeNaEe9&t|QUZKbA9;@AdNtwa}a`keOy=xx!@D>X{pb&vdZKa{0rQhl$q!d!Z0dwD5 zXAf8$d~$r4GM=%zdjGcKBh%fGc>{k(P^C?c-?=Xj7rgDAzcj*&D(oxTX;K932v+2P zn0Md}d~T|U#o)rjm#bzxvzroB&B`z(C;0wG;c&Oo6L~W8C&$($N~cZEFUYUSqs~Il z1k1pQCbS~Y2?ejl|Ka^{Hs#!G{~#Vw-FAgp=W`E9G)K4=`gr{cNOIr4LB4BL2K zsVX#hwt)qRvaTKb-Sf69c?j*yIec+hTZX!tUVI!#JN~WuLGr?fb)IlH`xzDugUKE? zyFWAwLN6g`4lV-@%H+}Bx)scWyOS+X;Zch?^ROjOPhg*>0a|PE9P^{U35GV;4S6h{ z1wKY%t9mH}Ep<(8N!LoYcJ3Q+`qhES!0v8yKLQAhhm#I%w}Zm1p%L|B!6)9?RN~G+ zK)=$@JIdbcU(YOl8D@<6WU*k^&_wS0*`_!Q;sOJSI2#FO)ilw^_upy99{`O9tuitD zpLU(jRImOrH1K9V-$||x?ge7Tu$TB~FPSlS*Jr#5LoOTFV@so6GmFy zN|cF(4=SKYFa%bs>a0Nnb<;34s_X;K>zq!19lRB7VlD}f9vX1Q!OBb)nznn8~B zXKx1UibAg4H5uJ6Twk62DaTFSgU`ot7lWI{Hq7sVX1j8q&xi)F;%~0NavgH$ciPbj z{p{Q0M-n}z-~ZoywVnTXcNsjgQ_RnFRAJe!G1vUJOfE?O7uzBz54k||)@x%O%s>(( z^H}864T?N)-0H>$Epk-c%@9E9W zH{%pMA;@=5uAiuYk_Q>(YKS`&Ly{yw?PD-Drh(XB<1>{jMD=d z3C-^qEXrp}U2DK6`-hYXGWQC5Q<}sgQ{nj*(DClN0z!UI{>5-vKHrH^otVD6a_3n& zHcpY>Gp{r2B!ImTD}z_FRtp6Sw_=TZeY*BYhVi%ZBf)BlUxhiugl;hi3ubz!+MP^t zP&m6aIzFqWWJfaB@od4mA4=hS;>)M8x9^r3NO#)OufQl&M9JR>aV8K`)ziGr(7leV z#_qnuzakUDxf+p{(VYquy%an(Y+-$1#+rp#US#AZ2;*@sCnrdKfR{Rxl*ad^s#fZV zXNAG*m}31>dG`N15~q*)Wpa72TEsilA-73IN-c+>99Mj$ z4n?(jn;5StRPCXE&v{HcVa>1nYk3dLW-zLwh%@RI&!6dwO)oh)uc*WUsa8~dRfGPq z&32J#*}{XSV`Iipua(2$z^X(61I^#;oQ4}4K$=ek9kMy=SDZ$*k&i<{Vh)Z#g-Gh!Y}$pUYcCVX~y`8rDZ_DU6V4y zyi570jDt_4Yle3eWlz4k<%BiWTZ8izxtK$Y2W>(|dS{nOI@U@kdUV{#_ptqvS~7+QA9V83 zt!c)A(oW9ReVI0}U%Fds_dTsP)7n3|QZTvzkNNRE)8rebav(1&p9(QHU}MA|mY%ht zF@K$(%%e%gas&5SZ?d>>YU=}IHd0+Y^$m-UCY~vvD@e#rFG5ka(FrQ7sBsbo7#Fr* z09Ql}AD7(2Ak3xxA_YSBW5Rr3kKAAw2c4U|=@s|YIYblb#F@f^#D&ilZgH;DjZ6)J zUcDZ=x`pCj!7e9N2~%-GF3ar;3Ogeh$tvUhJiw}ZNb8w<>GwPOnYW;H7Qgu0Lt+H3 zlV)aStOb{Qf()dv;(`!9x>#be32EQFS~{Ll+DoPB%v>Fz$2 z3v!Gee{OJ9IHwz|6T%oAp+e8%7+i4nv#-C);BVpW^HD0t5TlX{e8gw6!gFQWC~l~Z zAaMjED~V`!_;aT(=gHPXNpTKYE!_8O(w5JxXp@t@61xiG$KsDpLc#ccT0K{BbPA`K z&Y$coVN#he6C8j0XYKtT2`z&y5_jXrk_6j6~G3F<~sgj19{;=4Ip~>O<~w78jDX)HzB0Y!a90LrP9dc zy0)nGqJQzveBl)eMb8@zc@^^LOK;IyB7FFc;!tngC*K%Bj~iw6$W8i#iW|*sDjuf( z8JI&_;o!6LS6qq1yH2H+uae+fK#qbz881xA(Fa zz=W;EY>(^WhQW4W%QfF zjoBaNQxaS}wm{<%*&Jc;=^STnB**duwbJ)MtdGXm3-jb^zog#^N>j|{Wrhe6&QJf>|ITl zEDd{)5CQKC;z1Udk-=P}>J-N9n|~Gy$z4^f_O*nN9~sJpF7=RYBIrigS2|kW#K)o2%4iBxx|42^l#94BZ^}?CvSO#I zbQ+bt#EQ0|ieYH$} zXLpJ$?U7qa7x*%`RK;BdGKOy}5R4EVpqxed2#L2oKFWKH1_DoQ&L|IA)rx9NkR|meLhfBQSUB1SV zWuIN1)+T^NWUe=2L~xYFy7rl5s}BU`4>@?{aR^Zw&{zLqaf$*eLpaXGyG zvjI>%|By`t$_0b20E%_lIG*f0g=jl&)in`db^yY!=KEp)>;@CUD z*t;uB#i~|*w23rmiJf0BZoB|?ah-oZT)sl|{_NxJ`lI)^Kl+sZJLdmSB6QJpcyS;4 zIYy7yLzm4%%e=C+LT5};;>X6Y)sP5z?2x?G3zqu|B2JoWYCG$d)$QT1~wVc@N?r zMnJXYr;`MZ!r!44X}46fMwdR7F(=nd6cdFn)Jcrhe>HA z5#sI(v|^+L>B&Ci(Ho8La}sF3K#@b>TH-}M(; z1~bqwesiBgBNxisSUIkDIFQq}lQMt#;b31ahHfV7$-1A#>Pt?EGKTl;b%AbFw&;Uy zx?OYnR_P_B{*#r**-~7Jjw3c?z;rw^glFFtR>Gg z6_REetwICV#lr{dlg%FhdB$Rf2)ZF~RT^mmet}=q4SheSVTDBmRpiNGU4N~tZ{zFV zIFG*WvP{a?$>L@y!NhPc!ZYt?z4Srh+x&nUGttD-C$d}s!(thxw@kd>mU932l!Oji z>iy2w!N-^Jo{_{)yspIR8}UecJ}r9js=pCC*2kFoly3ke1X(MC6z>*=+gVl2%{FQm zo-MnV8OCe!`(rGLOFS9zQz|=s8>FG$ZLO>Bcg=V!3NME&@GChj?Nl?2Uka}-|81F6 zcugijE@7WCTlL9z&GmS=?`gj%trI`MZ7D7WQX0_M3~8M%`Zc~oZFq~OC4|4mDGz+d z2=^E5_!ZLd0MbWI==BBXet`bfw)DV7qAh5mniu~Z;+3HPK4L-hj(t0O8>cG0FPuTG zMd3}k^I~xi1ujLU8#hl`8c8|KIbApu4XMnG`lJg3xoxdl{m7O_X=O^=wf263xFIlR~%A?qs*~#>D zd!~$}%H{)=gu}(Y6+C(m&H884H(72PSoGm`Doo^lGzx2iQ%Z#V!8kN%Uq2s^>l9$ z`*yJ3-N%wjoUrH*p|f#Cnur(8*I^#3x6kIaseE9M%a=(zG%Z4IsV_octr`HDLvy_X z;-Kl7xwH;X6_wpDnOiQK`K|~m`<@Mtx$B8=Dx=$!G;YU5O~y^{sOWJZsaB?-g*+-7 zaou^%BG%dPZ+c1d^e&q{qPeuPzCRc#-w#a(`9R(E0R2!F?vO1as_9AL3$)d(4B~2g z29@R|YoV!kG3FxBUjQ?H??igen_c|;PTo{9Chd4r0->{{zAw#=%g6J_9Vay4b{TND zee6sE9rDc8QJ^4ygWH!OSIUSsD|FIB2sgY}a*tE+%Jq4*%Hv z&c{Gn%GW69Gk$-S4%1rwn2DWh?@QmMc)qg1w!S+a3l@c0r*A{E3(0XYe`{O<83^q< zEK0*IV3G<^lK#=8ZXvt0Jepi2JgKQ9q?A!BZEb}F%p}9(!4|aiz|}Z1nVC|`Q#X`% z;?v^Ht7cA%1=yvUQsLm^DEu;#_Q9?z&jH+RC+-LOUu#p% zfMS87RXH)Q^q!6}V=7G~$8bvIB)74vA^$JxFODT8-Sn+G|Jeu@hRl6Q;toC*w2Snq zflQxP%ov~ecVpAAulyiC|MR(vc`f-R%$`AA5pJNL!`o_=>j1BhXeZMyY2Bbdq;tm^ zEp&SMcgu(36^0ZIGuBHfs1#MXtXi7czZ95dXOGEe+#aq(J5Mhquz8co@imyD*m%e+NO@Xp>7uPREB}c^GL#3eWzXBdUd5F}$EwAN%!IpvcI^$kS`P-doWU{u zlM!SiJnhL@eKvv(U^}9Fk^!ZM-_$*G_-KFtn|$DUFT086sA+C0p5ra1O2s{jY<=S!a@~}VM|;zO z%Qqvd*Q&saa))ikt1ZZ&n^l(Nl1eS_>V}>@IAuDyvsXMny88@nfMkth&GP2}SBC>U zIfQn*_42;`!ka+_b1cqRV@==-0 z`aaBd;#*Zi`#Up`z$$oFrey%(X~?aRIlhE0V0;rj$NNog{Osq=`wb;B)CG>0(8Da? zN5~i?z*FbF`~^?CPDsK10HQ)|lP!*HTVW__Ke^E{MD6xRU-w^Hs$eC7M-N>;e-@sA zynHCiz}gR2Ai5{VeqO_4@n(Qr7H>NQ$BY3?PD3MDuU zr375;P)w;BW%4Z6LY_DJs9(7bC=e2=mWt4Ey|Q{^X%m`zI43J{7%*K1an^HRF~^J9 zNQrPV)&8L0e3Pd-lCn5G9L58;TO)>)e4rWZz#9Zm1NL)R`HH(&p>?kvQ12zhd@G;m zSf!9n06l6vd*9I0e)1f!5@MaPCe3MCcA~`pJ>XaMeG_k*0{dx#_&q@^-bM{o&0tr3 zIG@665I+3P%I#YBbyU3hk^|7{?>A9#NEwSDWy3$Dos?f?RYzy8P=lC&SUQ5wRO~BL z-KY2;LfmYjc0$uVjH(+&vv!>iA?*V$o$NP-U~QI3Uqi?V*|?NpjpsE+8N};xn%6ajK#$*SwpCm3$p+ zc~lzA)Y+29Fe6|vv1O>Fq~!0iV(ZIj_2RU-1LSv8df=VU&q7C6hgrT8*Y(1OQuNti zDr%j@J%fMXd9=JUoYPTRa_*XZwZ&^n!6Q%H@F0ASZk*E>_;c&YCj8*wpjn3a)2CNi z7lD6`vQ+sh5Aph5L$wHmUwTlo;s(V->iDAfNw|7>cz7Cq+e~<6&$Z7sm%Fb_F7DDS zsmw(OO7Xu~chKv6r}`-?2710F>bh=pDTKClNO+Sj6t6Sqx*fyRY0oOc9gvprvY={| z1U~h0v8%m1&_%fS|~Sv(ZfbBwA6haY9TOCO<_06{aW#uI44Gf9B2J(>leP34u*a{lcQH>erH zxXOb%UB8Q(YgtXhbb@87b=)eXf|5JYqIap|M?n8RCuwe{1th>9^zBgID1?bOdlxOa z?hzne-ytN2qj!E>p7k0N#n-S9jR?K~1~5>=wfE6)`%Gn!W*B+Iq1sa6xcUVhqF+=~ zFa09|32LkpAEPGuzt8!sqfz@9)()1Uas2%YxbE?Vg08u-#Bqag_lXlhd?_oul)AqDbDRS*#Bl7O%QoU zkz^Kp#<8wlsujocfNgqKbRg{5ZvC%=`HSSGB9Gxw9CwNR`%g4mqO=^p!xw8h%mI22 zyIC3pzH$S}l0xB?p;+c{c7=)7*1prQT}!7WfC4*!d)m2#xiXT|CzMc?Er~GDi-|~e zBwAl#@o7+R5h+25(9S}C)-wqqpWKSz?;N!yG?zd)z!xabNo9WgyNmz1EU#mze@4C; z>uN=IW9AI2zL{;NdOV9FBf#T$QAJPJ&#&k-rb+OdUH;miwJd-rRTYc$Vag6vtMo>T zg^m@f?DRLQiW1+1^A~Vx+DWXqFW(U5_}#XompG%7W>_wEbQMQ6{3p=+W;(8#OxeT^?(^96 zKn;A$kp9NOU3-sZkECPe*w~Ff!ngPr5$M)nNf zgMA|MQl*b$m)EG$Y?EV2oAKX-vFCwldN1cy3`xkR+(97B`ZK@PM^XiSex}ydxfBx# zJOJ`@duXq{a}|EN>=%Q>S-!P29xb?ZNnCj|MaY4XQL?ZGFO?6k)VO|`5vg=f!xc%9 zGNC|=A$yJ(H;-p{oLD=sZiH~U2X((m2;pO;n|GAVFRpEb$`sJlWm%oQt)^CUf(5-F!|xBNbqJ`ew#|AwNQ}`Nf{oxpZ01A2s&v_M-yI#HAgJAaJ$9EJBWI{< z`lKoV5u|T>mf)h;*9604o{FxB-IU%&-uEFz3IeYbkqNuh z5!#OaKW^6%?kzK`31&Z~LD<_9mVSn%CTQdKlCXF|R$Xf~r)RBP*0}B5iFrUe;&zL; z(Wf-@Q0pA--+5T(M_18#ci^vndBa<<_r=&r!Gr60M zn_;q7ag%6-E(%*>tgz&##b9iLXvnI5TAgaj8=Aw#5;Iw! zUdMI2YJdHki0Q}#nRAHZ1O)@LFd*XY*ba8~$KznXyx|v?+}M%dhm&CXQN?Y7DNgi$ z<5^j%sB>xY-1*zI*`=lY>~5U|put9o7a)q1w&bdJN7@X0>kiTe zFkmGel7I;Kww0uYN-U2M|HTWD;D26glCVg5`UyhwEzkEthV|>Ndg-@2O09y;g!k+H zz7YHAsd?#i6N&Kcqun(W97c}3Cy{Q zHGUpB<70M>(kLpjH7K;Oh=@oH|C~8wOHns;(v7)9MO&%$*F%&j4MNA5^xf=-H1%|I zE-7>5e9|Hjq8(d1BWU2dq`UZuq^c7Sp!s24TtDZow9rS2`BeQ@$K=r;f)wIF>Fxu| z6}qbCqodQM>fpdmU*3LpmXP}k^Yz^R(qgk5lfP}B5|?3u@|HhYV+j`&69uO6#H9Ch zqTuR$>bb2NKFQv8_Jr!{Yq;^%0KmL)@;**IZPj5i=y}paVg3V7e&1RiXLBEYGqa^I z3c_jSigH$8TuEDWhv70IHLu?O*N5-l1iA|ks=XY<-F6@){Z7b92poaqz5cta=;Vvc zi>!-eL_k)P;uFC?(xx)6YWBgSJkl;hvmnCI!mv5#{OJZY3DzcohcLw)aX4E`VJ&4! za+PT)@&}tw$1KCP>-%<55iyCQ?q5vv(K^XcCw;lKIJ_R7MaM?O})qac|ltW8C3_tJFBDCDD z*1GR66UsSkC0KK1cYKSs9|d_C zq}=&kw2ngUR%i~74V)luK&vi+fu(=GJJOc%@TuL&o>q{FB0iQW&BPDR-Uzf5p3fS)*_ zx2%}t-P%oAs48K^rg91v1^@)&OnWv1DSmx@Z=Q7AIc}*$ox|H9-JiV#=6s6@T8!Ep zC0%2bpMRggAU(@}d*bIu2gW}==SaR8v14iP$jpZMQCnWe?-KiBS(clK4!{mWX9rh` z`y)MJ`mJDA7^Z324@Vy}$KaN`;+Mk5ja_ZSHEdon)erUYHB`BFs!)E^uzV z`;Tb>KtsHDTb7wJDUcJTwUKif{+cq$Gba|`j*)W{ZtKn{v9soRRW--#hP*#oq14Ox zo)g`jqTdva!LC3EzeGxt;O;2AM1y_Sa=@m9_kg^9xig8j^J`e+K4)wyA9SYN@WXMF z_Rw@(=L%TrHsI<`92ZrtvS8n&XQ%qMx%(~1tDby9$97oZ1W%IWD-U!k;m z@%#z=QIaS8XIH=A;U44mLu#H+5PpH23kl$a5~bXTBC#F84M0%qw&jny6+Y^PZ{-p3 zH+)8)Q`3N_5jvC+7V3lsd5o8gt%A*Tjn`N6S<*jP!>Z~_MJ1#z( zYt{u2neLpkKpQp%Q#hM!^QHv;xzB0%u*IRFptUBGqm9?Gzp}247YT$A`hVtGn2JZf z(Wdtx$!XVzJKTJG=j?Lw!^9`{ShRBZq!~kV_!t1{)1^AK{bmNUj#3Ra$L`wsVi8}2Y>r5y%k7RZS%+}rqlK* z<6P!j2%!k@nz{JrGns2b6XB%G^`{S=t_JGK%qY;i1I42+9uf~ze#gg~n-TTTCXUp} zI$-R&{9Y4C>3py!{--4Oc*|_jB_S@~%fYg-jNxftvc$(S8+po?>dhb#yO=@xmiC1M z*$FXoDHIhZ^Elg)_?+2x+bp!(n5%#0?bdh5@^q$>3Cr*dk=p0MM2!a5kZZB7*9;Mj{id;WYB|qO z7?*=iHj`*rW$~@(pt2RlwHJDEqv>M9S1n6{N!LxLtp4@q*sJ%z<)&QC7O)*I_T2Cm z41{4igv9VpY}Xh|hWpP^J

    UU3N1tiqdC2PefAOYGe5C+Ce+@&puC1E}kzJ$fzs{ zkDC^ne{7Q(*lnf0@%j1`-uA87PG<}cVm=taf<|YtG6@*k81VJqS>pP{k5=mNI$?+M zN$CPXgQ`ame5$gfsAGeqB>g4K3X-2`0C>-OXzj2qby&eoc*G9{-=Fm_&A~!y&CfHD z%ZE42F1I@)X~IA7Z$jdcIP-haCGZu{_pQFP4mKL^CSh+({RjqQ_;8d-@3ey#O*MGt zq_^8!mptp+&QR|KQlG-Z3m$kj=>z~$SiUA->j-f0e}r*vD$o%RNoe(j{wGOR-Mo>fqJ^wl*QSfsU(*AIqZ2cZc6=N6lx#mHRoi?RQL6&J;M=ADSQd! zBs+!AQcvtDyg&6x=LroUBqV%m%`+;!4L@H1&-mIS!8J@@Camu$%k8})BGq{wl5ntn z6o=FGD|VV6uvKIhu1z7f4hc?(?g5t+egh+3@KhJ@u$*K(b8?zlq2#V0!N9SX?#bE! zh(2fJI0VH&3a;V0tl!`=VMVrh3 zX`pTql|FTMex^fUH8h}1dPyI~4%h?EYKg=%t+-4T$JPx#k*ch${NOYbh#UQxqlEjd zrj;*&>7#l!lxH@<4djC_+~0chD7Ym^kC$ZdixdjP614O1CsFx-%A79kZdy!ooT@CX zTyXmH&cxg~9O4lZ=fdo$o;f-@&y{@g%~dQAt9QsKX@Hu1;cR8q{&e3-{(SkdG#}oX zvq%e&_Cvbsa>JmagL6zyK7b!E?mb>M>ePU%8skrRzCnWid$#$qc_Z1V9V-Q~>iu69 zAoB1iCEfj7v!)QO_`)Em1fhP`%}?~tas*J@YkfAz`mfuc%sx8K zm+C*BNKDtzMe9V?#85WM@e`iVD)4`)4Brqdx2c!P_ED;>{=mE_pD0lxKC~{Ffn$70 zB|-S9%`txN`uH{|87a*~h3dP}sg@fJydQ(o?GEHFSKHCC?D-{;d?UNxo+%JpVHF3k zNTbO!W$@R7 z=S$P}gok5S>3nwD0EA%+(bGf$x(3EWMDWF^@8ndLFRULmm5rSqH-`+HQQ?0aVkfEu z|72ZA%nr_A@|aM(Zd-vB%Mm}V*+hDyce8QY(%S*W^9+c~cWw9Q2*V+a)o>Jdy~^CP zanOl3^7;mQ(=UJ5sN^H96XG?Xktuc@GDnQvmT7HS^}D_?4sr0jREWoI#0Wr(vxB{K zLR9XjPM9*8t{KFQJMK18DSKAXc9ya^tDQ(}L;203z6{b0w>;xpPx!?r0GD<1NgA-0 zi+QZ?k$-~kR}8B~JkgL?<=2j1_iNu|s(TIFdc*|AW^Jyn+zAZJdhPy{tzW*}`Y zMxxIpPYzT;Jx9pLR2GdYxbFQ=L?n_MzTWvUn08me-&S`4KQ#R5jwZsXp#Q?+s)IJA3E2(j ztHBpf(8tx_ja$)BIn~tV%^LPBeTs`Hs(h6MveW!y;3J?YgdF|~jL+Ew2vw#st94j1 zqc*|35gL#Kyq&oR z@o2T)p6m}vX9**mi`R$C4_>5o4pfHpB{`Nqt9xW9?z@&bQpy&(E*1In?mRgIe2Gjc=#F04u7 zJ_=5EqMtK|7^TrX%qr}nfT9igmLe3a zbjil=?C(BLs7C0RbG(e`s|m66+Y8H|ab04aaPjoN8 zJgDOix$tEq4_bJiIsEqFo#54IZm^#Z-|X=Gn;A|2HhTUZf9Kl z1CN!8R!>v^__RT0HJT6o-OU6pcE$&J`AR;eoyx=>WbUATth5NTHH)lyOZNWma58M+ zRW2Z4#g(;>qc3&<%-El(KPG8egG`khJNwM^6ye0k^2*#bV^J>Lt9puHTapbf!F@nm zUmzl{Q9$uf*z}d zZ71}jUme^<2>5q`PQx7*o*KUuFl(L|liXFh!mwaDE6(?Aw{H~#LVk_q|2L8T74gK> z?>V;js!qUlc(keuXnJH6_sfebqwK@=>-OD_t4en+!xR3#@h2KG{|2t_zH0_gCMN`7 zDhj?d8>8-}1aQ;~D6~%qY$n1;dp)=X} z^I9;#%>aIKaHAoM(vwEEbXVug!zKj~)7F~RBBl(=Gruyzse`j`+OU}0lusU;wP(EB9x$UR!K?LG`kma}5(ZU`KF|bf1`J=3x(BdsBE!Ew5~gC3DTQY5hNX)z>ZSA(J6jIx_}ds-2w{8orB+dj!~n;;>!S$BRqi zc5ZvD1CJtw5x|`67kO#-FMC3Do)A`k7>#k#Tw~+92Q-$1Wc&XgCf>rW3CE549-~1* z5$RBr4i)JZX^>_h-QCg+DoRUtNOx~^h=2?!sWD;*j2rNnc#1t>i)^f=v^rS(WzAun^=C>C7j`|IIo7m)Gui)Fkofbc*kw13No zog@heY-9NH>RN@_J7MSHHZmxxoj>vgK8;XmxMEIxMhjn1xyLr_^meI9BPq0`;fN*y zf8X6;wXF>bG~REb;N?O(XF_K^rLT(cAvzL&1q(~lq<=IWan@=t z_S3apAbHYY+6wI_SSfa5l?e{r!hgc4_7+i8E`dpKusum4rIHXDaWayQ*)TKhaR& zA#`}LSPNF*Ph^;PX6romg!=K9^A^Xy#j7+^;4$W$zes&S{&$F**Pg12%^O3UuYoiy zqJJvow2uDW^{{2Y!=P|m*9h^~YJvqg2qj+OW?!3La=Ji4$ya8|oYov>pRhUkwfw0- zH4`0i2|LTG8rH z`gs>v^-g~)@*{UhtCkdvq}MBw179j0oTbH=S7W|5rN0;H^(uoYx_$Z6IAVn^pjU(R zMDh+T#F?j>L{`#&u)a%A{7@diV3ouJ(fK(UmdNl@_huo=afLRx?CFD8eY_hh%U4EU z;sNM6&lppOTDBT9KRx1|G2Q`0J0p4ayC|fXIu015 zM7K>jSN4vrVUr-Pf7~Iap1t#vp;I?yr(M!O%+oc?rL~mi+BtNgUpPPNq{B5C@9G7h zCmvJJ9Vu+LI*fbBt7B2(#!Sy%-%ibi3w?cZ7Q8#Kv4u$m8vcPaTyq~KW^EuGF;S>9J(ck ziY6y)oIRxihsw(~teQ`BreW|}EUuQOU?Pj=Oi!kH=)BkDME|TT2NoRJ;F2Q_ZTphj zbKU5%d7IIPQOx(fv;)ly8+>qFeYYFiYdb0Sn+$JMoV1)DB}{nBwK^RBRpO|Eh#H{ zio6WF5QFdhm@>B$3jBA*F?xwRNBe~RkPK(GM9UV!15$wEXA~FII@b#S ze=yW$BmN^8iarqy*X*7TU=grtv!J>i(!1ESylNIOrvdypwc_vq@fEc;P`qS_^LK!!0H1_?F7SOSwIS-JX#}@6R64jQqj(Ta5Nt$ygJ4 zo6K*aLtDHQ2m72+&H(X9c)jV^=jzuT7b5%OEHo*Nz4gLA-kiTTZ@w$J0@`&*fdjwE zgEtcwyOF-MW0(EQ>1TA@i7aA5`@jL|@So3-u`DlMGypP^cEA!4N$wFK-LiSHAT_0w zlT~YsjN#)reXRrv!WMYB#drW8f~V7^m5e_7-7sGB3M-S8C5Zm0X`#Ye)Z49|rLEDe zn5*41FLGCvM_E_Hf1DRnA;EOmWhw@TQ?z8g7yY?brdE(0bu78W-uU-K`3NTCcAFSO zm9eMl1N}ij1hgfV`SW4f)cx=i=?`CrdX{?87UxeQ0bmlqA`hEaH%iB1{^2Tz`*v51 z9d_mDg0-`(`J~+ajrCA{xMGRcnk8h{@DS*vJB81gXHVW6jtjn55nN~4>ZiRjt(@YX z(6#hDlU^A*bd6{aq$;tj64yGAEj12Ex60-IIkCB&N=P1-HkYqxW;sxxN0+LYXm{hL`UKu5r^0@A8O)Bf0Smc z0j$jj7SX1eEM;enAF%O=lcsmQ(`f?cJ*MM+VtG*m!hV88NSPNOU-q*-7UI^m#KwWh zPW#lTb&ms8rSb5%v9~iaV!O~QV9aW7 zU%a|=PA)mY%0r|K@NO?H#+hspw#lF`^Hnd~YRUYq9QE^3@=pXB;MYzy~{zmC}@@v`jljeLjD7M** z?Exz>^kSwoJdB{}3L0BzL*tOoonf^VUsie=8Bt)hRoNF@U2IwuQyvEw>rn54X(eW} zD-tEjf1oqgTDoQszV5r03-u+BL>e5)|w=U zIDwpH@$bC3bbus^EW~ybWHLTXtuh!IsAQ6E|RXz)Pvg`~^F$@TLiaMn-0TlX2>wh%7~bKTz?3%+PAvp{C%oPHJZa;0x-qZ==#m{uAr{<=|aCw`^Wnjrz;8AhcitQzextR*2Ufj&u27HCkhfj zpcrN~JEEzRTJVGEcmW^HU+kGp zk(BmQU=+-WJQY|zYeyBE*Eg|?7+9nq{~I6n9WAyb5Ym61Kdku<(4ov~MnG5s_ zB|R|@2Y6zr=bk9V|4L&?xhy=Yh1swVf3r+|WG&YlkWmjt)T+I>C3N08|X47tO#(^QVDmL@)X7O&k!Gk?7p{^q}az z`Ao)AP)N@LQ00|2`18`2&ir|YKlc3;+d#uu8W%PgkCYfZ6%f?zM$Ttv!5=Xt6HjE2 zN_C8VucY*$xBo``jwVTNu-Leu?A|l94})#HXD8HI_jcQ!Qp8 zcQ=-d`XfB~(f9yB-|lkZ?UFM~*cVl9JCe{aN6}P(>WDT#NdnOG{?0gJpWE()(vP>d z;aj>Y`)e(W%LTa2!mWh~9*ax?S^#S!xSm%Ix)0$KbN5@4z|?mU-3>Q}BS$TGLJU_7 z*G1g3Hhe*wpz=e?DSfl@fc+!H8-Mw6TKYlOAgWIaWxCq0fkT;G zh}Ee{M9%)QpgNMq6QBYjeS_t*iI(-)%4O9f80degM{wgx&SU?wK`)|hip}I?Y8I14 zfMtl=U*q*)d$xnsgy@$%-RElvglpCvM#cZeoX;J%{SX}F+Iw-X*8J`5gy-c3&%4h& z4mD{Jevwg>+r`_<4ZFH;wT1qlr}` zA?{f99Cwv){V3P4NicMPYkv^soTk;XL;obfIW;bg1Ewkqnj1=2@EdNqWd(QQfWNIr z$=?9a`Hj7@?uUX!4LyV3y!@k_%+Pq-$T#F~wEQ!i@$>c;&#arlVs>2lv6dL37@;fv zh%Q=MFAq%m2*0W~(U1Q-T|45eUy|9twB%D+K6e#|5s)?L23Yba)R*>Y)7X5nHH68Y zC6F<-e>1S!74y$K#ftu*Q=rX4Ba{C;8_qFGmoZge92L7CG4SVm12A*H$00j0@8w$V za`~ng{idaRyTeXpx@+NC z+hoVq5c_f5tud!H^t*^&z3{7&-d?SN&=}8HbkuL#(WHwmWE5j(F?#NKWa2OF@&>-% zwPkM0S%;U0Dmw_3{_#jr_#615ZOj;(=0LIb%YPh85{@0rn3P|ZL^jYrR24tM{`O1Lnnmy z?~TrQZL3l^gkB=a%YE_(V%h4x3C)5(ZvEt? zDnd8;a=2rnb08pd9W8f?n>oZ?wo>K$Wy&1nOdX5gor3y!GYnx)nFmU8QPMSw8us_) zclX~%D`f=kh#&s~{@&ZTLkfj-POP|A6z#~~{-ct!+Z?WjA0@P{@-=ikTcSiu;QkG! zqkqw8H*v}AsaZH4EHtFKHx8`g2ZrBIRn~ZXL=3yG6`Z|^+FPb_!o_X`(d$U`J6)~{ zMELcrhey(M1*5kH$*kd>0-@Og? zI6w$?+R)}Ry=m|2Vr`R&WhWH`_?b{;FL5a`26;vaNdySF^gKu$`tZhQze}Cs#!U7` zpIhPaQ8R%iGXdG*x%=uyjqRQPGK}B{9)FG&$m_=}#p5779kSz=WCypvygax0FBVd} zDMN&*m)=TS6JodtBehPZnl%`|J)mZuq~=^*Ny5U&a_uSK$g81HLbujAEv-8`rXs0&kn1NGUski@XjhDH=sDYcYYiF)R7Jm^wp=gRgbXr6$b+Yt>VT_h*Ic79kFv8Jo)M6# z^F*nrW8H=z%Vj+Jb>*$|E{v{q&Al`C^KA>p@dkqv<`WB2J&Pm!1vWG;l~Tw3*afE5 zFQFsnIdQF#}S5aq$!cD;p5s7FA4v7l%xAE^GcXP_s*&+qyW7lv6HwPqj44oFri z+KmeCTX-VaHQLa5Eu!g z$85WKGe?9R`M4MP1iwcRNZURb8~`X+iau^Xm-(kP_C4E)t*Wi| z|C3B(O1)aV1u>F^@Y6Kp)l+}A0 zvmQ0QJYCC#%jKpdBGJk|nl$Uzhl$PUYUJs{{6B^y25(IBl5WPJH+-;zpa{Z8n})ug(TGyNSvG9<#r0qIwjuU*-`P zMLUXo{UDDm4V=NS;oys0P{S=b!c;UxOKM=0sM9GOuuLKJJ?lO%rXgvWtYr|mK4B7D;H#MQjm zqj4?*zye8{Cy(sBv}j%NSX6k0nTUQ(IYvXk_EbC_&!o}E3k(J41efp|uV66lC!s$E zKy#MzLRO|?m~prmxOc0q##3+7j%6r#kiUn?CN>4n_nM-&{T+4T+;{<*6|zndQ>}*w zhC1G#RQ2$>X`7&85qB$tJ2^7;q2&$C&xokmo?elYa0c*E2WA`pE923x?<-$p{6HAF ze6G#A{!eSjeGc{>MBv%XnkOFNdEmylgAG+lW<*JZfyOXQNDmMwOL5(>7IgFLlORqx z#QGKG?TdZ}TtcA3>zEw^qxXO9$Fr8-A)hHvP^Osoeo(j8`UuEg`#4LX_fyEbYPaTk zCAy)4;!3^Fo?hGZ2lxWxU%S;5kn{~u@|xwFi0^)K4ud1|rFuZIQ)F0ue0dL;Hpp|y zfqS&sr}CK$#6$11ExwkACnm=5w1bq!eJ@pMO(--^Q~88c2rv;@^Q!Z0+QT>BqRqO0 z3B`TjwAtD$pTg5vy*7)4Wqn7nj~+h3z-7}IU}Ds{K6o>}vKAvzbzK*6)}#jg@XQ^F z%iFpV-jx6Q3$X6D261M(1~t%)JR$D-5Q_oqcB6VRh6mU-hWKZep0a(B8#5Mb5Ca4Z z0+R0rD_L4Er_Z7qR*58IHl!WCFw(y~BD2YKo_?O37Q%A(<5mf8Mc}I2-W;&rrxgYc z+I(_w+0*aCJ#fcxA#@D75B*ExC7C#e#EuP|acpdKPK6~E;G$aH7V1oVM2ub7uv2I0 z$*29LYtReZ&Tzp?s*r7L?+QZh+2-u2{kU1Zdc)t-+uq|?ADqsW{y)#pa3S`t*WP2cKQ|fiSC9i$T16##X{o#u!jhGr8|=RI{d*A zlL%0oEds$;Zd0(^1oZO8+RLSg90ymc5wa4N1Mn#l>+uBrRRuUnnrv46yU+I%KfFkH zAIe`KG?)Gy;xU2IT@?!c-iSeeErv=$&nu|9_(PUku^2p^ zXSR&D*Hk{x9Bv1@BAR}l>{Vnia07>V)2v2|6emMRPsn~2|ME-8aI3}Rz5td2xFRW< zD3olzAmlCBDXG7ji|+#8>9xr&Pv1~q!v{3!7dy><@e zihrGc+xX!-@(Dt?{}DmR+!dNYDrr?9ex53J>=7f083&0O!q_vdQmfrsuR^R%)Htlx zs_C$Jj5vYzV^~Np+fG6`v5BjGET36cqp^p3aHZf)+4hU@uQZT=$tNQ&Lg~WXGrIct zUzaZ~uTE^!(Lsei8UYk@NGIbpsX0Q`#PZ%rsz*0aF_ zV6)90O3HRgzm87Gva+;E&|>Vxi+Rtj+tn5$i3l-OTwZ#Amhge;Ry&=)SWnA-Z1~Bvo7~?tdcyf+0M5)Z$)8SwbQjnkyWTezb=ijRMe#4?Ir} zetRyPdLnR$5CYOKvP9d;k{)z#6G?ALuJW?YBPkUg48-==tn-hfU(GV zuCUr9(t=>;=qBHt$!cR_s>yvOb}zuWLzpwaNK>-rr_I%eO^PNa6AKGcpYXb5|237? z>q7fz^+qQ10%HAsQ+6uIlT&|TH2V4?i7QG4tRy?5NF}4`XCw#cAUR=!uay~$x0?He6!oX4jD&sM-;$2Xcf@Hex8mMD)@ zinePPt@yfGe4uf@8;I{d?hBHGacPsF|6WBh0#H z;4b5QIl7sX)6=67Uk6^0Kc5)K5Ge!ov9eD-1*H`|@smh<^0gfc<(qh|`TMI`&sG|R zpU0Q>hTQoRi4?7{qAT{v$e*l>lnl0j5=4hzYu~2K)D{LD0N~ZQ*ft^_z|%-ujP&Ff z?nm?Sr=EeEZKqC#18}hSJLtK_?52O44^#BNzb&$L`;qYd($uyPs$6sy`tw|^9#Pt5 z*DY@aV#lkAnuxxFDVHwz!Nx_;yR|h{Z%RVt9U#^V!5-c9ET0Ry*m6zf^{LvlVQ`vd z%~Mr%*P_SKHexFzKY1m65@O$e1a!sLh%Ncm*6RwE1`=`Jh*u$NN|8+uL#;x{4t>fA-yvyFRjGc>pTl zCwU7Uw z4~Rzd)-GTJi;Sxj2jMBD#MN^TkubwgE;RetuW`Ma{63A_Mj> zVXfxuiHj`70xT~M0F^o+!Gh~$&k3%8HPS^5clcz@+EyL`Q_9FVbH4H&_h3trsy<`? zHn*b1dQ((nE*Vf$Ohk0KYR1-#boCjz+rY%n&*W~c@+FHgaIctCZv3tmLm@tV;pSNn zG`%^)48HnjRBfy>u)je^Go=X_%F={x(lxiG8PFQ%65mewg|}HebeybdM=$3chw7ce zYw0a??C(CO3pWe88!Yq*f12j!XJIE{-OY0T@~~LsmfbUl6cDx0*^hn z?-UFbJy1m)nlUW@U3EM5!a9qfYo8KZn^K7x@PeM$5X;haZ0<1Ml-`Zf&m-#!QRgPUEDynfZz;9#T=@lnGkt(OmtcNa#^ zv+NiOHt|_=&xnavlD{W*Re`1cL!qd5{R;Qym^-`9hsa#PhCxqn2T-45Id)_HL{!x zO<|{jr4AzsB@WM@EF1p{sa1MWc8A>Gc{3KhndF}+3R~dGIKN|(85J^`l5y?65Hp&V zS%AD+_iP-p)S`s-OpG3*!eFw(Pn0IN3kDIfXSbP^#N`}ee=ICZfZ>RnHP^Yd4On|vIvYy-YE}f zgI^15f*AUtS0V#E&?~)>EIh*F>6{PPv+2tc;WQ{ZBWE?np)2#6$xP@)AJG&6|B3EK zOl+V1E&ryYA9MQI!Fo=Ac|`i%NdP99AuZQ^qw3+pi@YUD+)zbOHh-b3YX>RN!KzwP z)2nK!OIf>>be6JtX43)Q-+$v~+MLVWIH}HDHNtml`OHE|i6p-o-w7a`#!Kmi=eA4p z^|zJdbwUoM$wH&4ZDYiy)M5T*|9qxk?3xqL|BDLGp)m2H2?pYJMnbq66B zd*2ldm$Yy{X~+0(gRCur!k6BuF?Pl4T4MKF)LaIc{4pY;;2HVO2Mzc>d9@vU z>e>LWhC}Iju67PG_1LHn>t9O?ow%ft45A7PTm4uh6-ulhYf>f7_e+fROdla%%~`#{ zNp{WZvpWM`tP3NQrtOcezQq)v&D`Yfm#E5_QEQtGY(xrHr^x*Xm^@V$%g021SZus! zQqh|kM$^2y>fWU<^Lg$5?OiM%OWC~+szeX!S8W8wyWHSSVYE`HxcZ4`cPOOB*omf% z_zJ`8-_?~)Y`lLV;=1?=PXD`Ml9ZX#=(;Ra<)Yhgph3;$viqpe(RL&ugXMN#U2x?= z6sYk7kGRYSUYG~yv*3re>6ovGsM=o}Rl2t3-YfODQ(^Fk!sp*_)Z15mVd272&rah? z|6VZnlLBv?-rkhjyol7H=4ubpd`>#=H7UewB{J8H7p%*(1Dg$(wmgok|7bMuH$rFR z(Y=R6L3*oOtnD}$`uM4-Xe{kVn3kjbA5TCar{%P^a40dga7mdi4IfNpvXco{WDBcd z?)6^j`RS17{)-^3uBjpAgC*xRF7k75-}@xViI?K(OWc*V5B{{O`LNua1hU2V4P!PS z^lV>}4OSuUt$ij3?!J(^Lc*{Rg0PT_HNNE?i$R1yUiuA4A_9UTxl=D#YgA+3xVfMq9#g{%|klBOo9AQT|@nmq3%ssa9s&msODkV8|OWL&h8*}+x z%@K{pZTd~j>%Ntnu1aZ3{wccJ0#4}J{Ap;rwB_pN5fvKgrc;QPsab^35_*N(r4}hr zgbDSlP^4cobQo%<)t-d~R2MyBE04I^tO`k{`JaR(BGS(sJHrF7Mn{{RjOs`!-;k&; zh_o5oq9{Y4)&dJ_(wggf?8aVz7YLGv)eGQeQHPB?QRk7Tz-TSeoy>mtjogWOEI%!0 zo`JnQA%u!h&`AzJ1t#Vmo1sVtU;vs;Mr)i>OJSF*h$liH*r~ge_LrB5(+lB8*0C%| zY+!RSOC3O~?B~;GrK1B0hHP3acO#b!nO8)Q9&h(nmrULv6CGiOAaiRmL}2|r=HFTW z^Xc|MBYtzIth*x+WjkQHUF3(i$#AZM4^U)tH1T0i{&OVsI9K3Lby+&)Su-n$4FNSJN2thq)ehwh16JH3<}%av1B2rjAS5 zn`NHLp68s@P6bmDM>PI7D2P#AQ*|X{)Zd&CHm6Y;tli**V1`nY3{rPukxE`Cv-ddq ztlXo2MIq?399nI$=p!@QGTI-efZupQCFS(jO*=<+Vm~*XxI+muG||5Bcgf99;KB%@ zTd78G>vs0r!`1Z72q$G;&S7eZd3$2}%U4lkG);dn%`qc?^KSbGCar-}?V24ayd6eq zbYFE1kj5pm?{6o9ndbW__R#}o`-Rd2d3Fq}yoi4uY%ERsxVHz^Vej4W-m5%VR3N$Y zgg-}i*l_qv+RRee5%`cv-fRJ@r!H*FHyGP@{S%2B1_(zgtSJ0k0Doc1dQ@jpPo@XV zS?I>`y;*+k%f+@yhJzYQpBPyJ+H8xoLiNLAXA+*mAmpD~nQI&|WAubCiK|Le{rUVe zz6V}jDcRTFDHOd}+vC#A{vGFH;~fwF{8?6rGl;;zF**^0w$>#a;Fl!JG3D zY%5qCX)LSF|7sN5yQSvXd&?qho%vN~{4LrCXVy@paUbl3tDUo~?mrE!kuKs3bvzbN zK{rCLj7LTzs!m?{07mgEqH;2kzSYT(sLJKGaz^c?|5s&z2I`E&t-ovy(S*$H1-kzK)gm0mQFwDWe#*E-vPb1K#fy{>e@))VT)TN4uklolq9TI&=kBi^C_ zm-c=Ey$fI*pml(^51$=xrwQbdA|k>IZJ3;)L`G`%looE&?vIGe7W>F|NP--JI{4`& zfXw;2(+D5}wk-fzeU97?g=E)<&y&3u(fFM32=+AEAHRuFfNz(`U&x2lK((dtg8Krjoj@Z za@ zhX*i!wU^D`XN#lCzwn>h=}}qhFZb!fH5D`IEVvh!chx;40DqTq``cD+v`ljA-VWbp zbUkpPdBEyCVQ&1ETsdjC)jPgoIUBB)VfGiGvJu(E4whVAX0d8OG|h;Tt^Ji{VPRj;;MhJb*yKZqNFm&4(sCL!;Lh zW3z>rH#gIrJFvT(sZ9GjUMX}bTWez&>OM&N==-L5P`FVco6%!OWYCyx*ewrIXs7kG zr&1ctGZo^s!n4yldVsYuPV)hP3i-DxIk9SrSY{EOecP0pA9E_fk3iQddu;Zh+?%!% za_MJ^(o{m5|2QOBkG!llvGTgb64c*9n@a#gk3@Gu-pzl3wk&js)wNZ!t-27S#U>bY zN8wl1u}ixrt>-r{O=a&JjpS?!3b1>8?(?}v9aoz~Bm=4ZBY#1Zd1KA-VXk5ezexWQ zM94co;HKmQvH$z46hLL%K*?EeFM}^Xr|N+wH+dmF+I$-)o$WRt6cht^-brPKm2mg zm`)ZLrwAj$69T;4SAh&ZNx@6_;o+8f`rTesHEM5R94;8A&i_NPom`bv<3oC%#Jxv& z#}rHD4!NP}a3Y-{a|-NCsP+?p9iUCosdK?*fAj>2(;=R&%Nq|$%mL>*SP;$&Vf zEDB?C?S(Jli-rDwXIcKv99drfbUcI~G+585kFtiDW&Dt0i}+=2^i_}Nz&@;J{irtV+0P%t8s*%Dw!S-)w6JuUAmGR3 zeO&zPzI@=&9OO$HdG>7sOkr`+*j+JEt59-YSu~-oYaw{)t(dW5_v4#-zlG;YUbdC| z!?fD^Pf)JHTakbt&YL60K?hE7aIHwk6YkL&~7Vx?QvGb;*!>p@?iC(@9?DSdee^P#t&}+Gpga$|SC7 zWZqJs^K)B&UEafOzxT&n;=j*|8eV3$WpAYnFnS+rAKCHQFYeUuL$a?e8CTVDnb!jUgW}iB={xs(3$GVd8Q7p#$Mh_0dX(#$SK}e!>jrC^ zgZkC6dQ>kc)#d)bp0i2_Gk|E$`XHY@iO-EC_c<;7r32+_JaEYqUy|C`%L5~!MCsh< z7k+v{eY?)HhgV#(OBLvVp2wj;ncAb4b`639g77u$3Ev9PAMk8sm>Mc6Pn46Hd(Pk$W9U@mrf-^ifJ&0`xNtYJ@|o9qE`PeNNC`P;z_|{%4pa`U>Et0D zdlm6s7R^p&+~#^Hq9P3dYSiv4ySo1C;UP<9CZn*+{($C16(fQ#(2oPZ((C6B#C2OR zZpOBJpcUKk%oST6 z?>fu0#A!B}1zyg1@>FC|6qYF)un3R~4fY)slZh zXZ)GPTV=;M`J0IA0@m@VwqP_QgO` z;F##8+xLR2x82ChWjp7v_9WYh(hwFj?iEz>EdZ7=5bZlOC*)%1y$WA*vE@u?g;#v2 zb!}+9CWtyHpH?9?Lnt@whUax|Sh;%con~{g0`k`&k4KFaHUW{3=nRG20sP9J;cIKw zVyow3o}09K*wp0Q@Go6i*YJH{M*NS{=Tw=Fb-&3>;a|td-Lfzrk&Qzpc&2Xiy;PqQ+iH{2K7V`{c@4CmCZHTq zD6U_AT1oo!mF_cTAXp_-IH{w(WmzvatV8?SOKMN&Soz3iuD#@WgMObgNS4dc7GbpX zqPDQtY%OV@xLO}+){Ebnxan*>d699mR@`+WWE+a<@3}2`ywh<@&-^I%vm|N=mLl+D z^?GSBzFt^jXmmq4!!tUZsh$n)XF(se3aQHztEC|Dh5&=i=lOmg1cf1~2Lo=?o^@FE zTVpi~EeAX!8W#)?b?MwjGx~AX&RU>9_S}m~RA@h4TiagTLH}KC??C}tC&B}A(9pd$ zDSoz!S?s@Smo8GJDPu()w6xs&L>P|@#s)C+UzqMg5?bx^1^$~KV6E}CY66N++5Of| z+i38$A~ME?70aF$xc>*b^SEcDiryi85I_q__J%w)KYcOTrpZ^GNXcomE zJA1mfD3Q|Y0Qk|%A{G{7=Z3vn}DMMd1j{nXVAZ_ghR{Yp1LzD-B1Aj5`SL(7m2T zPs5`|{uO}jcrhcTikYxZd8`IITXfgqc_!c)l;{3_aPLzz7K1Tjz z&HZd=s?|^LCV17*VTW=SJVH(h1uo-RRXuG^W|i{jQCtUuDG`_E0f=f`UBwGQ^#A<@ zIBW4`=6BzEq`3(#l&{?%e4a%@nY7 z5q9`<8XP!CZfT9Uy{0=%>V&|ryv^atd8@5feRH)1n6k}68~sWacGVus7Y)K&0mH6w z3F2UDQO~2qno(=YXL$Od$t|=UL8}*w%l7vHofF*$g0bZp2hA#{w?lo8Rul;zguWw` z{$UgphqwSBLT&R|l3C0r1H2y;)131{E3 z2$^UjJfq`AoPR(kZ~a(%K9BvSMpORPq7JjX{z|QgkTETbG4E7Bk5c8xgENuZvsd<8 zBs~%dHSYyL`D;cyu^?`REl|Xe87$_ zDY1{u2(1fhSTK}+_kO)8V$v%cu?e9^1QJuz$Q}JI9*%{$p6FhO^%zXLzhbEDr%}0%&9G2}{Z4*J!(;|T=GhI~$9$@xlMEDSShpHc6?J;M z^^nO@{hkkp*6oxH|1??jqE90<>+1btE%N%Appadn(JSnv*r&Z}om>gom%~lBg@+fX ze?lWXjP|)S9;k<=U(xSU1yvaBv6V*(nvj1ol`YV~=*#7aNKUs~XeuJy6X z{6<5XSvXKXw8P$kr#0N~^7&AUAb0RG+JZx8hUrNqsj5Lgo&)eb!Gk)$LzQa7eaOeq zbkA0KBqvg^;H5|Oz?_R|x4+-BG)0F5(hu4>uO~{jYYh4LmMQrktq?=gvKPQfWZ{`aO&tIue? z;!nx(Q+dJdK&{Y8UKdERR%YW`1@|)+d5WxD@R%?8+3F1EePHtwWHe0*X}tVk71JvZ>cxq9B4$sgieTV3Ag+TwnoVI9nXlJ?p#35~AdG#}E`42ZI zJTb_#sZsc=L>ymPlHKr+LlYF7^Cl7}egfSv7EQJbavNIRH*Wsnx5zEjyi=s5lN(4; zi!7Tq)SL-0TP5eOAaJ94@f!T+dhKa{_^x50domtz6L1VBWxHqbZ5&W10TKn|-L|{Q z@r~Kul5{&J6^QSn^aVZKbKFNRa_1VHzn1dz52-|c1gkpsSa;URQW^?lzjA0df~<3k zAK7a*uQPGp{aAUJ*5_s4LSgx6XuuvGtp+qzfsTa#7`QV~>gJ^GcuO~(ci$N-hQq(& zkjj=RU4*D`aJbG^Hl$`R;RqzgF6J{ef#^Lb0W%Nl&gy9i1C zbAd8g8cAcj!cNHz+ukl`g^o_j-Y}bj-Av{$-Z>XNDneq-f@HDBmWcEnDJ1rNP@iET zI^&>UW&67Ecr5nlZb+b*xWX98^&&`J{eKkB!TK*fko!dET9JVY8fZK+i9eJyqPlBDCjTg!?T0Q2MMN52N9AcQ^uK#!Mx7K|<>%5+abN1f9v;Eg-N0Q*tS5u|O&nADCdxfvL?IZNe;k(h3 zs{^Hl1R-2Y=e9Ath)IQzW}Cs0IFl86S-Y%qeo*tKjHAKruvn~?`;RX9DN4xuc3opg zRYuFZrbIhn7e=`dOR&&!Xb5WfJ0kLE2-~}xN@^6)`#1YXg33n^F_h_!u{UR#u>5E-7@i|R- zNNJ3deusNMDf(bg(Z$iIn(285b19m^es}ngc8Ua_5HL#WA8vi>$>Xm&Pj(Fbjhk|3 ze1!|BaxSl(5UCrg`d2&O|HmnJKw0ht?T;=fa-r?A1eFsQ<1}a<5}8B4Oowh9g%bFH z<>O}xVm>5tt~_9optW_W{Vm&HgEFO&j>)QwqevVY@XkuVOkkhu06mO~TdOvy${2X0 zf9xORfQh6}m+@9V6_8hms*ztV)vnD8^Slx^wBY;FZc5E+RApf`+)lnqp6T0OUXjBf zTWVoSWTFjpa&VX~QVp-mndXS7HB(s9y;{bGLGeI#QT6tF*P3(&yZgJnX+j zyGs_eK!Y2N!?Qwt`Nbd(L8zS$&UBJBR*^Z>tU=u}j*7wiVmeR$Km>Nd+4e;W} zFx~l)%rEUD>Jfd^+EXykn81_YF~^6dG+fg>}vGuJBK7K?`ubAf!YVfKM1qPh!!My4L#2 zIy$1&`D%G+_uqn(skAIBG4ULo4)4!(-_gY;2dmE!m){y4R7~~LpVG1lCyk2Z7DC9m z2!j|GbAAU9h{_Pp*G{b4154$rE0bE?J+`jR^7-X26WET6GOH<-%5Ct=>MV`D@=j(@ z196#OjtCfaaV~nEq-2$pUsAnKlwAvYRzfm{NO@BW+@L*(j(%e8eN3(W)U$2%0(E!G zXE~~qOQG+a$>cVse|*w<;;JIz4dVv4N|IKUSD|zTS0*NOJ2Z{?iY)RWrb^G@I4U^u z5dGzvckoskLG(HFMSQV4Zt-dfKxiXx_51NwbznEvyH`NZHyd&4@PJ1Ny-;vZ3B2g+ zv`-B{2lGm_bOns4YlMqFC)hH2eYxWN?-xPn7n}+A#JTsCk7_L0PWOe92{yuM#Jpyz zz7s8e5qrEj(YhytPuP+dgNJXr!5KlBDwgQh~<#_Id-=Z zRAv$xjBJJ1mHl##8$VSM`q*pnjXFl~stRx8*-~oLtf{klrT9m(H7k(72+1n2bxtNV zww|XE{eHYdrK<{fcxgn`P|_0;cX84()ABU2&#Z}4UB6b?EwyqM@Jc+vm`fUVxIq z%74cE+Ki&L-_FG2BQ&b4SuTT#29i78M{$_nzOs6vyhBnHKdDz|jC@8gTp)<87buuMi$gf{K4#rJ)Q!WZN zwY)X=!sWT{1ovScNN~IMgD>S)f>BQ0a4*z%?Vu6CmV=9+6TXGq-Mfp&@}0@(&cS;O zoP;aqOYRiAbQNFFbt`;{#@OQP!$svoZLq>sF5-i>|L<(i=?~CP{c44WzSDVU5pcya zw}VmOZ5<=2f@kMsWH72emv3!UO7=dA%^Q8Yblq`nDSNXKCN6UJZA74VN)fdJQWQc@ z24iC&e|K+pToyon9l$EkG&vT7f*GOIBr1^qwp;)c~W06?wt5)$fM-b>V_92yMa$zyPRy!)I~eo}zX7m`tI zo`+A2GX-!5Fs-W1`XQ9oN1=Q4=-Jk|+HZRlvKL~KOW!oP&!?OTr5GTsbMYF4N+8JG zy}3#D9bb3CA&~G=91_EXiZ*WRG2#cl+^G9Y16E2`iAh=fRXEBN(bIFl> zXeIXf7QF2h#6tIAY}ogf59b}^-K4Cv&TjyGv5B-LmPxkzT0U@3p=tw9=ZbXp@;yzm z2My6!*%@QwN`bXSlXtTGzMl|ng$2lG)h)(-Pw?_(jmD3W_og_S=Chn^1gTJ)UUL4+ z)$EU^WEIHN=yR$NE$a@xy_(u9(aV(_(WO4tB51rv5o&Jr zfvEZiTd^YT+Jz3(c-2&a0L}-YpnszX!)o83%$LCvSkGM=nRg@fFg2TpS@n|dx*TwC z^f)x&-zRubm0ek#E+EZ4fiI2LjrfK^0DY|cXF%=i+JP&0Q~tv8>jXRgaXGkP^q111KVLw=>gufg zmL*u9_AEL(SdXAXxPNaQro0* zHpixJ|4Ff;Zvo7LkNanF{BY@NWJP@p_rpav4yW5qT7KOeG4{7XaYvMTl=dO|<>KiCN}B1ze`A*C1u}3FmT9*?n`o)V zS%6+NeJ&E1skhHl;I$MuvWXaAg7A{{o&SZ)?bn!_s4{*YJy->nl#vPQHU7ysN(?m=BXjNsH?4ID{P|Rq;$p);lS^oWr6vcrL!1ccO zBz?7mJ7`AM0T{WN^{Ecw0qX$w4SXk(Vs=yT{~Kdv&2qm%Q$*8+@k^LImJ({7Jp{Bj~1%yDFYAKKB&n0t}4O6n-R3WWWj7IkBvb;i=#j#(2>HFZgQ%%ylcto@WL6jKP47rmw|%u$!8T|ZCw zA=!IL6%N}>&O4X;dN$-V1r91P{{O)iZaN*Ko_d1+CC|9`BZH4G@JL@((du^N1n5o> zEDlkL=~n=%7Gb!L{RzG-udEPsJzMtQJ-7ACBZLsV)c;P# z=wO+sUBmKlE{g6h^w@s0WN2PzZRm%~oA-&V%{;qTQVEol{qQbsD(GtDP!70W9YbXG zLz5h}McY2LH<8U2V}rv%#01IH!LNRt)^ag%n^XSu;7N@>m5J-`{Mv3#?X(SExHV6b zICMOhoLp~=l!{}-xN)IDLvI5ohf_11Gi`R;0j|(J({6_V`HaElUJL6mDP6SDw!MMW zPwcI`)vs*-4kCziHn41J^x??`mGgUMwg>6(*mDS|eJ~h<7!rNf?cr@+6e12t<0Hq> zEV0v7nYNl`I?a(9@?K_ zM!U*x4gHaOS{Df72LIu~g+}PllqIWIf-atv_Lwsf|7NE2jU|=B+BIec-x_yflQ9Q_ zie5AqZ0=aQhm2R7Q)Y)joZ#4!*Ekh7Wh^g*g~(1ws4KN#klK(v7PXCUD8i5pyYfVi zR}jzTX-s9gS4E}1JhcxaZS4qLLxwdcO8y*V{~l(DiBnT{){1i;U{0}_#;@I%_WEkf zpOUyMl&EQ;shMM0Nxtz}vfGe_Q&RhQ)I_8V2@{%aI6uYvs8w%d;`*ScG0 zJ7slHxPb&dZro9m{th7(viJha0LuV; zXyK$_wgDsC<8w1dZ;$es9;(~-=+U)+(@4e3O}$Qz4z&l~g~50jI;;l5d_EH2{Vgb0 zF%@3UBER06@?RXTH0Zs>-NFVvH|Eb}{IsICmv^Py415>2@F59X&vlji2oB)d2`0F~ zy@HT^+|4=;f#4=*wc=3e=4fU~89MZF)XgDkIMh$v=Dw~M^@j3_n{`D%Oz9j>0lOa} zY5C~W}H`|{`#MG_IIE!_z=-Y5WX|ga@|>wUiKcSe74;W_9!Am7(!-HZ1T@& z0ai|XwKB}5IG2NJuwOLpJoi&HA|mz2!4IJ-2^$^;qqAhaEN~}Xn&?j}ja{oW6RND9 zHOJt$m%k7eCMAZMkq$~tg>14u&HZR=&c|nyvfHj~RL@87fLgj%%9QaEB8m>~ICnSQ z<>hi1v1xJZr6)RGl)@v*OsaQE1n_kI`Qs7mVw(XN(yX?Ng55$lOP1j^ZTfDqo}rl)30ukh*1>#;K3SF-fj>-0e;p zQTSf$DS#hLS)ePRR*t02E-&W?8x}>N!-yUDB2&vJLgWewg_=y@;?TroHhIcMnRk4G zZ5%n*)mm9Dxflt1^Qa;TajYxAe);FlP7dA-n^jdJE}LZdt-5&~#;l!{?aB$Qs$GG9 z!n&emp89eF{&Eq|t>-^CpqsC<+`hG!B)L1+NoXqt-1Sn(j+I~BP;1wHr{**b)Z|w1 z(^ch;1vUTU+|6wLFgS0oU#!`Lv14&2Iu5ork=`FB<>79h4{PuX7>6MU_5CfXiz{A^ z-HwTJ)KK3F&Oc+*!I4Vn(~e{7y52DlE{%=*3NL5#SNE=5#{VfEoWH zL0x+%#iBB$eg+CLUN*@?A35m2v=r28MvJy91@|sX^92$(-wNWa56xxf2}J|luW2E%h<`c`2s-b?S%O>+wH|-P2?)}ILd%(hN3RBR zJTW4kdB6Y3;0MD|&|shEV>^FF1zX1^sE9id&=uzNGw0Ml_OK42Ya!eFMg76}8Er*N zo>!de;@|;{)x&E32Y>keo@64fr}Y^%zHjH*kLs1wPJX^G#*q|3`CCkiL7^)jkjGv? zjExdbzzrrP-aTMnHg$0Yj`c2$?KCv)xa^E9daz^z$mIb97l>elY60@E&Kk=ptPY!I zk;-0J#v;=PSwa^;qRDS}WfKLoJg7AO5|Y=a{QW;5jc)?W^OUo^SRz}w8&w9%W|0>s zssIpvc?Q0CMh1Z4Oh>*Mj|ErMP=RwXVHn>v-(1OVq@mq{VBzn&!v!t>dx?U%Xf0I= z3ie)iNmKWhEsX>f^vzhhYKvL3&9uH#Z%ZLo-l369uw!;lNL^`3ou-f>%_}!%UmIO6 zFD57HRE5`N_v7ggx<{2(?eC0w)GhOg zod5=Q#B#d4)&`l}hGL7%l0m=taB5Y@M?OI#^q!sK#o}s3xVsi8?hq<8Hb9#(m(&!p zW=EA!@Ut-=b&IF%nYP!DYTnQgb33|x^=Lear30_Lj%2h|We&{3OiFgLf)Bic(o6>H zgdkMA04=wj9n-aZnb!!?z2EC0%2!ux&Zy%srViBTuk^#^Zc-XX9s|>k%()E3b>=*Bo;iD&Y?hG18PFib? z`nYs38RddaUuTkX=~xe}O{OY8rRRWObGv@6NG{8z4BYusr^p`n&z$n&R-Pnn?a;(# zILhp4cXYDMYyIy?)gN@umUTnSFARlKro`)fL3$R}1Zz`e-pQXDKC0JiuGLg8lP9!D zAH#-=%N_7{TA5l0LZaGrdbVG6VJ)sK`==dkZ^y1R7y$)#=FW$>Lop6ZTs6YoIPY`s zfZX6FS@wy2T>c+R#dy|pf`L7A{ddP@Hr?v1C-|lTVuaHRMh@<{(%!mHhys{SM)RcN zR=adR#;Pj(d$aN)vQ|5w3!A~XV^4lYC!VslYZgA|(=ieR^*u3`pU7@QN7c20NKI}zXJnwFIXk>5z zxOs504l}JdN>hOt{a-J@&1K0C?FB2@JOGn_`(HmEquJsNYwP{5AG>?R+T&O9JI z(Uhj5orlTQ^Vg~J8#kDBA6p!GWzvn_0>JtYY-hl&`;sB>%RVpH8Ac%Zw>yiN?q2um zWRC0o_pmshgWC&iP-pc8;v@xR4I>J|+$oLt01=(#NBcx|7_>t*b)4cRGCJ2?UO&fJ zJ`HQRwSPvV81}Tw&#rsw+ILx4*rWEIdGg1%i9YTt$!04x%%hxAy{$ies#ndr|2aG7 z#9;psJ0j)%0#4hK{BN{fW})+1mU#J6WIA2F-o-jts_e*pX;qMQ2S5PF$q(lYKm*7) zqvj-&sdP)LRe}3;jPfRfuIB7J{Dv0_+M2}U8?@WDi5*#jlbjbz+Bzxtdw847r}iWPON;?;i1@|fHl2V+ZcrGS-hJmxG~QL0bl z6?7OfOv4Z-2Adue)=*cxa`>&#vfVf@W+M6sJ3UVwsNwYt?Qy7G1q>< z(xcEoS8|z0$hUA@UvQ%p*)h|UyTaQ`Ww4}s&22!C-{`zRc}TXLAPRsF#4|b8U(4!D znZm*d#{CbM2X^JadrRw_O2sE_oj(YMpk71s?XjhQuTCwk(=l zvN5+p#=~{s5QADv{~O5_)Y>%_gHX+;CC^o&oJ%uJHQr~|lqF|L;8$u+Pk->94B-t9 zm-K{=CXw%e1l`IZWmaI-Y^@`6I+`K+Xe0omj1&9Bgf&e;xXn9l`E%PwHD}s;0*eLq zqurvP^V3V8*a*VRWnV4jLl?}@vd%q+bj%O!4lL)|VCFB*)L%#-$j4D|4GQbmA3IdN z)Mahe?e60FMsZplWGi6l5FCRY!%WU6c~6Qh|KTaEWKGH`>n^vy9`W8HkC5LcPGp7L zE8za~4Jl%Z=G)@(dI6Vodpnj-$hrUO>>bN6hGB6Sbsr;Cn-M%e9HkzM7M154# zSZm9_vK*vy>!N?MURmcuxY3gBf!noGcTSsWZ+uI57E_mz)|KcCpwqRDccYcxi+(;D4}OmqF-V zq2PY(#h-o0UrC&@g~l+f;2H2PnC`*b=bohuz}&J%m-~zj~`>*{U>2~M- z?c_C|G=#Dfeig|JiA;%yPs$txN;uB1TPbjg#WBm9QBxor;P-nA-c_@s%DLJB*xxY) z2|2&NS5Klaorck0ooejImq(j6Yosd&k&Bj{y8^{ax~fdO3s$%N3OZc>{o|2k3a&NA zw(wWnVqPMs&0VZC+IE%^gNoQ%r8~Oh^KAdaQj}0NnpXA{g0~ymFdZLujSSeArJ+Gp z4fvdkf?)}cjS95oQ)sCP82jeq;TSxQe$R*RD_Rp@c7(_h9FKre=WT#!*qAd$o+jkYXHBX~+raRi&wDS7sce8A_)Zq|ju3vKx`Rf4F7 zs=~&awKL($;t&O}24UJ#1Z}u>!{@c{{&}CoX;@<I|4_{03 z!vceW1#$G8Kh(GoMvC>p?cjR3FMx=EbuMu+3vnn%@<`>l&T?0pQzp={7z8}YXku-; zj0p}lbvSb1poGr$@(qmsRb{Dm&6r=uH#=K&@$`loKId|*(Ml2UquHHY@IIF=n{zSS z% zN*}eXQ(2_s8T`BxMM_`b_+>hhvWqcOlk2b;6ze-rq;bx20PK`q>u~3q6jCd9{}wtV zlj`ap`13jQUM@lLGZiGoY~IndWl(3rqSEW3Tmy0GsG$;7qBrSc87mv%Bt2_dmz}Q~ zI*CRZk&6>fB#l4zO(20a3K@V<=^QtAoOl(SO1$=C#g6tyCsK*=>GT+s{_-1-(eMdC zA-#4MaUQi-+Dw{s%=pBTcC7Bvm$>~Fff!1~uY);aMp+JvOBx=nGV{Bv-`-gV2=%D( z7%?|`c&l0I-^$nu*X&idF*`EJdA{4YDmfu7mFZw^GQ3 zSLB=bSEus9k0q)xVMoCem?&0P&M_E&75$-i*aFm&1=YnrQ6Rz*% z^?nel9_$t;ZO*BYwJ|~S8?(aqlSG;&=;q_?IEXnqHdqn8G`UkzKkF&;zap7~N+xf&=8S_?x;ZANWO)_9q67sOTdLAQ(KCTZO8Etu(ic~0Iy)~11 zg>VUY7zJWqCUR-V@kGw;_tRR&x(CvI{a&}r>$H;e_ocyljuiTB`$_X@Vs6rH+I_3T zT-ngoXTIsSdwi-@mdSR&5PpxxdK#M|!BEg<#J(5W05|xS7jN4K9@uoh5R56%zWseA zXBhxCkyrfgA8=!Nb!D~vPw6UEr$ZR~?V>ykdCx1DEe(-hbxRHSIdNFc*}E?x6?x|- zHnC>?Y^&FS^)h}+vFCUzoQuyfVaHKpqEflD@>T>A%jge!A%7_{hdSrWW$bQcAwruf8$^lSALV8!+TB^ zG%b*!{*|pbcV8x+FI9AFjZ?Yy`@o^}BAsA8Wy z6PIY*ZZ@asd)^S@B?_T6?7~+XhUnr~>KC)Hspr3HKm9$r69QZ--yrqWu+QSV@nT(G zfW6@gm`utpI%IcM)6n>fq5ra0%KCNj^l?qldJ(G6?ugV-Fvla)pwx`nlqk4CFt3iF zd8^~4nyL~nNcPBM;R(Q;d51~V?Vi2Me5ae>{v|tN;H=&SrWm0m7%8Gy{8AJLofSC! zVQA%s& zB}c5bMgj0No7THkAz<4)7FF7~8*iith0RDM2~i)-3_$00N$nmL7Te;s?Wwz+S?_!h zoJu}&a4hupAXiXd*nYXOyF=VK$oW}6Ewkc^^lLd(@jK02XPFvdpA4cwpWTKEAj!$W zDDV7BKQY5SXAb1$>~Ng%gJJh-VIMFn=^)Lks+nRsnDe>D0G%EppzrYR!p?&Mp<_{P zDo#oDT-wXh#f)H#6kDMwzqk$NXF+dz!SCXD2Pubc1t>$JeaA^2wc0@7zFmmE&tL_7 z=mO6_NQo)kuOy1{ZBG*(JltYsx~!=EcAnNLN->VF>SgS+Me65O20z5goW4$uZ=dNT zIjca*ZSeEUmK*i+9dEs)mtHcU)|k@dl+3^2e&R*nW@~5wHm=i+Tga$+rPd$gQ}c?Q zG?OstZa^1_by;O?QizIvEeR~%itA@$d^g!hG6^ZOOT*TU!+p1|=5(>1Ca`uL2=1w7XvmwLy`=0@hRvaYxsA)3(4{7$CNm;Nb{v?sxg z>kHS9wmc@J8Rn-X-z1BxNjNXFH^GA<GuMaDvO-VCaVWM6_ zoh(^SZ}`6Onv(ETH*du}PP?%R3cllmT)$Fy++hVqGzM<|&Uw6uTv_vh7w(H1$mp*}T7M7+!%0txtHO2x<7LN(;WC7fBL?GIiq)EZ4N%bZ=#@j>KWg*mc~iB=xb z^)S7m+q*B!=H1-6`NN3=P3w21K8_oYn{|;}PF&;1@-ng%7WR!A3uOwh@xGH%a!x&O z0TYFi4CnZ|W}7H<-!BBz zCe`N44X-}__yl0Ut3-tWYRmmI@N-;e5N&f0pLH@3Vvwjvwi^?+r%U|BUtKQZ^M-Q1 za;cwwsy-{PL4E$dfV)?)Yo20}gMk>YtI)RAY(}qkB&#@l@65rt947x4z>^lJZBXZx ziSx;ajAzg8!)#UN?rGV+)ogdt@XYKT>`%M=6NZc7(gxh>wZL6aZ+2}8gpL(7H+gnlvf3F zl*#9Cu?>7#5a=rpRdjeuZm2YRIG4A+`|BUNn!zX!n%!0f#JfOEWW9K+5vRItXBL6CcgNV#@B{i{^l2SGk#iQcPRi#?ym6sQufdKU)zRCkKZW31>|<6graK50_q3Tnh!i`|+b z9Z~P7Vu+Ke(sn^Gg>|G#qJHz6*RITJE)amp3LJ3yJ&s*A=#6C>y*dI#-_^?T2)x!K z{q-5_R@|5R$d-2!==`u5fOxM6{ImSvkqQ)q zV^LmuIy$WCDf}U2$aj8w>GsM2;n@7`_s_X{q?QyZn0+^JBBBXZHUGkzr2MYt767cH zJ3m#KbvIzuSJx=%Uq(X{MkI9~hS8?42#C^EyMi;-RrwQ38C+eNs|m6e)Y2gjufIl)+IuWr*; z@5-!T>@C=$x~xnsr$5a_ZTpLyv9a-J;5A&Rsk_c!8==~d#G_QGS-CP%#P0&%DXg?V zONboyuM_m2S$u8TNy}LyYil8q~+Lcz%x<~#I8qQRwzXJ2~bt`#(PuvRiltwBS0^W^7 z*pgD{3Jgui(xx6u8cp1v4i>tb;27kmPuJNNSC~MR4l`wO77q)a94_1GY;jo&46L@} zC;0jKLA(WSjsTC=NckK>>2b;HKNvb^F#qCVEu|lWJQ1fYn^|48Fnu(%gm=?G!}>Q2 zo^$ew77SiWAKv)`fM_v=3HDf;8JB~7@hZ}XsKh-M}Xd2Aboon2yw`It)mUX)~ zPw-&|hu**MOsk_zvs-*Eu$;0bM-&PtwObV7f$q$ggk#U*O zm5;jHlQ9691@@+y}Z0`VaHz}sL~Y0#pG;Wt5F(f&}p-& zxZ{G+YYsA5*Q5|>r&2SHST2B(PEoYq3dJVN%E6BXU^4gtOb5QT zv(Xok)&vmpvvlq3%K&xy&`oWns?DH2;&GeG+aHZ?tHOe<&(|d z)y!ChT*Y)y!SjP7&osYC24JohMxC412v^o0=%;R!GPl#k>`TN?DH8jass)I>AINwtf9uvF0rynyQ=oEh@4>ofNwqgvA48uJ0>yux8;Ml&27bJwWPPs zfjL(4>+-QI4Pixw7fn^@XL_)E&N_KsNN)JrS>aeyYa~+Nay+07_^`Ziwibz6R5X3C ze6Q?*CD>PmA`!KNz06?H?)KRky6CM!obsB%C z_D0_o;7XZIMx_g5znw|Oc5Y(NJ8!W5I)KRZIHcb?F7@q3Sg}ZdTaAx5IP#LK{2#y!mpnMf2SMDNTr75Ks z9Z-T#!&Jky_sF9sd8jdXhdI>L4+U(-v>ktjZ7*x%(sQVel z@ZTXtrOp{tZ2@JJrWX`^lK3s!){|`cE0?*bwT^#PT1ubidvvfCa=`Qq(gc(vAEo*{ z>)=OLIQ?4AFx1nNF{mT79o^G3)S(tob}1nr8dW#n|7=c{`V;HblFCiRDLZHzLSgPiKSv@c01@y%>d%82%w!BcEMb7x}=PhB7w zCe$p`=zRgL{)=d?JhgJ&2{64b5TSa}vFcsmRnZ{S9F< ztCiySt2Cg`Esjan3VRXRGz`SvMF;GRQSX!%KL`fjZ|CmNUOzl{d(Uv>!X2Et$+=qT ze;ig<_mtVIt12z}U6~U}weL)%wS`Cdv;)1!F~a#)VKZoLPsX&~ztE{a9KX|-=8Ntb z)#6)_XG$w!NogL(27^q21x>estDt%9+jtJVjW~(U@UDjGqR<8+(&@K-Y%8Uel`6R_ zpNUO^@wnmlYsiu6;0uO6{ht8`VJuUt#rUWOLc1~DzX-!_ep-Qac$Orv%&2<)PJl(? zOIiXY>Ke-p!|alE;U859V^n^Ju8+)Tvrf# zy1!G}l#{?Q2ioN1US>Z0*d6R<5)Yq*XnJbd81I6 z8|syhWKKxw$8S77+GuP^4Rs8Ecocpf07P`?PBtj*qrVO@WUJZA0t5%e_N47Q4Q;EB zz}Y%m3{EQitSGvAfwZU%uD8N*UcU*G&wXE!+0}brW2Of<85W$F^s(kFQ0#E_fx_a& z8QnHKsYh_Xc5f5v_MMF7-?N%PqCAf?is6jV?-VdkoG5)2&{h@xjwy4&t?yChkx1Oj zRH&K!%)rvqE(5a*6Y#5Qp}20IpxYAa*Co$6FAdG@V}rBOdMr9KW)`$#U#AZTuStzv z`AS)xF_hvBNMOIlfqXpJv*Hq1N;~!&!_KsJuo+EBaqz}vJFgkhwDxsD8Uo%y z3-o;awA#3Tr)I555B7j10pDgalv`hs?zHoG2*GxqMCA7O_v6t^mO={AxF4$&DRS|A zL8NwjxE+UOHRZ|vs>dYaBGAPiL~6Z<&Hf&6 zf!0$RWCl3}k{9FKU`oGW<72&au(>HxYn&_e|?OCeVGo~>>LdKTaS;w>0L^E z{jbocd_Y-6*n`~Nlu*#)kiyqVIn+1%xjc47Eb*fY-|YFt{?9|hapeyuc`)_Bec_TJ z#U7D8{mO6IB8YcC^cU^Jh$wMZ^Fy1A4byd#j&tc|qnsq`Lcx>?KFf<1uyZjMgqZ%U z`R}>|he$H>#T8^AA*mT}f6a%`uSq^zX>z5Excy89j)ZDBoFy`N78~YlT$aR{>rOk4 z*{nA2j7Ksr_J_@5jMUBfo{mC>Y8>qWD(senvCta*NPkxE^tdQx;A&ufoDGptdBWV2}{be!U{<`_R1zl@MFFf&~M zDj1MEH5k%EEL=yKtu~c|bgs3kwkxN=E>k>;e*HD3j&^5PZFi`aG@>M@Q05mI4m~aC z!|?^JK0(k4EH{a-!!@6`_5l&|z{w(W!GF6&tH=Rw-Xk=H1*FewQzl1Cp{fwsr1rOg zW~jUK^60-z!ix2B0|pm8g7ils??|K_9m)(zjz@Qoq8zTae&y>mk+8x|Ig6FDHHUIj zfe;gJqs0Z1DGk{#yy2po&(8kW3$UbMU?;YJ%vzxe85Av{k#sK1_vU`HV-36U6u#gjF6RSNQ9+>!?)Pyen}b`p0SSx z$R#N+E}O3u!>}EiH`q4mNi|!Q?=L z&!HU?VD-u33C5#+WWX0q`a*MnTR9P~y{|JjPdqr+u#;m|Lj z&1xbf=b_#9(y4B;ZrY?EdF*`sgFc8Eku03TU{cvy&VEFK6BWsGp0Ei zdL_TY#W%MCYSgjr6dtDXTH#vr2Br6=Ql-U@!PRTXAx@Klg24T6dC~#@uACB|AH!%C zj?Xdpw6wuLH@_+l{CO9+h~4xKsxRKA6L&9Ig)pYE$RhvTW!@=1Ty(l0Im5&L5LxKF zRF8^e<6y2BRtB>SBLYW;b;=ZOI?D*#&()17xS6%2Z$Fz5!R^%+9Xm;^Z;H$?Wlyf; z2WD7;DAP<$acX=Uuu!C)Q024;r6%9xJ|?ThyBlZv)FjIc!EL9K14*(!l?em+7s zV5L!{s1&MiUUFsTX_wBMYe(&q`ho_7oPfjOK$l#;Q>iZ;<8lKXS{2!W>Ag2%3BK{p zxi#31!AKoo2VvY8c1{)Nn5ed7q<3xodx=7iWAJNdu>|G7@Vh8Ol?Y$rGpel@_d&kN zpPy6q__`kaAd=&N-q!-GbzVR5EOD;PlpmkeG(5_IsY1o)vPffUOMX-Forx#+WLqMp zDK>tR2t%2sTo{~mVdU!v3(ni{g5jBb_hWp<<99)Gge8B|dXr&d$)q2_Mf^YHEw8DT zHoCNK`yvNMh_vN(7aHqd!6{1<#H{N+>bI|+UC^@SrF9|N#6}Bk%wv}J^?nrXzSQWx z==&@B*!5r9zir#You75SA83+Z9~IOVlHVFSiu48~Iju~yBFxQpucSdA#s@TiB`23l zhh%1qZ>8CaM7>^gB(?6~95OI0kuBW$D5@wFFZrEUPwDA${gWY&z|dCWW&KPeynwQE z{1@AH-oGbc3La>G;)+J9(J=H{MpWzyY35x`kh#9Rq5LTVZ5x!DFx?x_7~ekur6zp= zKW(nvP9UQ5GtIZ&9neg61f&7RmUE$v0IPBc); zirD-f$$_Uh9`X9BPa538_?Ba-Ba3s>FO8=2#}K&py9#u3n55xB<0tdOuh-!N{)-QFv5-hQy0E9ssQ?Q5*W_8L#(B5yBtJ{<4b4Fntpw8H zFiBP1_|hs1H= z`s}HcTx&;a3 zcQYtCLury-K0Sz6COCvpr)1kEUXreMBCFI!4b@$k4dk=^_q+tDG%2Brgrv z^l^}e-9flfAQouT>%g*Zl0Z$4QE208|MTJtDo2|<*9jtg?TBB`uaZ_XE7Yud)-3^D zYeSiBOjOOZ&NJwORwAQwYRkBS}CP7+A5^is+2Vb!&-qX)h`}d^I78=Wb&z4 zZhhE~58}UGz0l7-ethx}js~jwKS=4t{0Dm% z7#Ox!KG&ap?+-Yp>AJUOMPEmoQkGsD0j~X@JFk+_`7sB7z*yuiQYJXkYi6z}w#DEEesvihj`cgnXYRHg=>!0^vrbB!9 z_Uov4R}7VG&Hy)rNJb;#>J51~J+U~I1M93(Nr(qq2evvq5!w3 z-x+#nr5i+QXpn9Ykre6f?vSBjXeFh)q`SL@?v(BZ>8>H}bME=hbHDpXto^RN-rw5w z!+2QbGc&v>m0rxV0vJidK`~v3xF&-xmoj0pQc`se8+NWB`W&6JvEL+hqTssdOfW52 zzM#OZ>>?C4LttyZ);g!c>GRQLLh=^HX9PlD2AeX`62NH&M@dzWKE5;aY4T}Hz1 z7NQ57?_91PtlrsshPw|_Y`jsrtVYL20q(NjRteblF(KaKU#7kw)0vLVMuQd!T`K5{ zS~I$WH8P(Bh`@z&N@N$|Ei+mWgl)P}Liyf(#dmZKnh3pgvR!1u1d%%@AMea(_Rx#nrT-9s#s{4j-HKrk*;luL* z4^F`VbU-k+Mp4IzLc3B=)n&nMm9eTr6m_Kj3v|PzgqTy-VuIhGqWIA>o6IspZF4y& zMprp>Ijvts`FCE;*OZCHY5Se*CUOlxA~$i|u~k?p zdUP+bN@YCx``lLo*v7|tI)a|St}6d6A!2VA^ZvAc71btjE9fGi0Ya+W^f)^@!_ZRl{eM_o5h@F(*8m8B;d>Aw~( zccI4fLO2h&UpbXZC@rZPoq>3E9E4@9izR(-foKNY6KF9@?kC&{y-WcezD@ZiK1^Sh zLXF6WWmY6bDg@k1Rzni6*|fOb>)pTl;IL%Rb&?#PM9NT_?9vYSV3m68K)MYm;(vth zCes{n9#KjyJiG6kTq%Sx`O{YOefcNPQx(*S9v~naXqqz`R0%euz*}RqMhs)+{C4j> z7D5qBdZ>wLnQ;j$u5*aJ+!;L9@*bpcA7S@<93A@jTiG}lMG}iVi^pkXxX5T`P~_c% z&{ST2>D{uUA6|=nmFuJRX?k$w-y+5HqG*ak4Mo-!O_J90a}9NMiH_$S)zalBH542+ zQkIzKvnJp5n6>4zgcii5w=)8mH`@UWA9nuQi3%$Oti$i%3nW{o*OOvZN$clsmw-il zm@g5fs*Mgf=TiIJ`Wmt1;J$wAqToLxLlUc*^ryT$)$Fn3kDD&0z6D6$)QL%{?1afcgYiQu>P@@u?=^I zvX{$*oHB@c=B}4(*R{$4xtrt}2Z*;Ml#yk<&A?uBKhqXi9tKbGs#UB@0EzJ3``pd~ zkwzXATN?EIWEO83QlLx6ho!nA@?szDPJ1>@j{9%kThGsui@XQobdjs|KQDP~%kYs7 z_IFEq;_jx<9lq0-{_+*FoiN^eaCSk?Ij;^!f1G3Y4|o8_UyDJq!0AiiavV)%Rqyvl zOh|>2Ka$J!+ceg_ylJim8|9c>lw*hmq@zsh5^T;-YZYXp`^ z)ntpqeA*0GIp>l)I;K<@9ain9jd$ThkJ<%?# zt@l!Bx7?}}$HgH4z~$$pz~hL+6*_JE=q(j%=5~NL%#395{C?Bsgm!*O2J|A(5^y=n z8F`GmT&qA{r3KLuYie@*>sLv*`V*`510#&?*$t2oFT_t1XitfpOGuOiPey+${*x6i zUT^-R*tFc}&li+=c33buKk>lc((7CyNp({Z2D&fQQ2l(H=PhNUsjZCcNdE?-Gi<@9 zD&D9$x$*L_>Jqx5EUke_5|H*YS&0!&#IBovsRS#-O%d=B&?rgd4yQu&Q>QpxzeX+W zjfoJ+JcOQxUWZAYKhp?`lS41J0BhMMhVV}=o(6B{8w32h=%a7omVbr1yOS|ul{@vU zTTcvnZ+#OQ0zTVsU!%?selznjpq9|ghP!XRcn@#WalKVM5_7ZpF1)z3A2^QHJUA$YjMyO2s0iUs%c z`vMZq8x{sY0_1w3^4Z6sS#-@X})5H-$^JE{J? z&@w_z9V~;3{xhEbFN;H4fr76B{5bQW32kKKd)~ls@GsTf82{&ro|U0Lee-OMAX4it zc|eQJtxE_|n=YCoN-tMaMT0gCuq!=X7m#R1q~@~n!Ej3hBSJ2p_z~J9j@<5f{bjt( zdRwcX8XcszcIePv+E6)zgeV;x=EK!Yt?uxAu{+OGee{Ml2-y<47rv-x(Ov_a zg8!OnG0hfX%efTk>vwRyE{@WP@O+=(KlPB6Jpw-Ke~?dNiTkt71xT=9LPFB(aENce z8j**ZjYGS%0aW^2tv<;tS~DM6b%EyOPElNTs(|$6MSSl@V&5o9$KIWC2gz)+dc~^c z&JPPL;_*74@dyQ_H*v*b;Ulps0w$5=TAjqVsLfG3G&!YZWg!%9b!T*hNCWHjJk`gJ z`6)9Cow%%7jx3T=$Wir^4W)FYr_(a2TT2a!zmmj*v zoOI+>pQ5_QVIoREod!2)tMT$=$ykN$$Rfj@K`bcQ9@`+#(*{jr+j|1&*IgWXel?*j z%w+ZzDBE!u?}DBcN&Al_7wwuqa?4Jbd%a-uhYOH00#zCO`--vULHYLr>baAmmf1OV z#G~&dwj;JZ8iD3uTUIM9HM-L{+abJ#{l}{~#v71TL)FM>8s#RPjJVHlxynVT z%Ry5Js1k4vh$y-ACddLe_uu(A=E*IJHbHJZiyGi9#CKC`E21k}#w{bD3~zxX@donb zP<8@D${6ugOCU8j5j#N#pmi;C4caNhgTqTjfUr|X0q91Uk`Hm@v&&KhMxFwn&R~Lt zcOfcNkg0knC8e*x2m9pkTw2^?Ye5O4%NgkuMq@l7G@sjPCf}F5s6D0AvZ;kXeL0RN z^$Gs6H^EWCqz}n+00w;D%LvV(h6Nv~?kQcz4&;Ijx2pj%*H?2m8W}nduFd946|gF< z1D&^*z5SsFit*Wl&tbJ$q}1m=ADeOrdp&|Hfuq6SZ)x>euc2;zWt+y@&S5>^EE~^^ z<^HmhpmA<)u6ntPIqogV+{+z%(>?hn`#S({Y9dPnF2Y=+oz}qw6+z-VJ`EU*78?ne zzZN&4FUR}u(z7-v{uyZZF~fb*qrn=_`PO`w(}(hip-<+J%Gd{O$MnG$tt)2hdDBTq zOeF=_{24=Mzn+5ILO5rLLmTBczvV<3r$*0rxMeR6#G%>v<)~x%gA2v75Z|n{JtP7( zSq{;~mgHm;^8OHOE2yh_e1t~Z zWt1m-KHHwTs9U^2)om&vykq6u_q~9W`-m)e9l+OmvP?Hj-8NZ4WXnY0HAR-o;YTWq zo&m%4K_|Mo5u2K;ZhkX0(WZS-`^Ei%IW2x;3DnIQ8bd%=Ppu>#&9o>v8CLOwoHe(F zc=snb$<*%K+GVPK+1_y^f_4x+6Er~xs8MXT8>ZHK#JLsII7sz+(NcZC2Ie7~UtX`C z$SG%Gqzn7%ZClaKT!-u12WJBY$Xf@x=_c+)?|$M)tV8 z1dCWV>wD#A8rq6XUqhOdal}<}9*ih z@jAH>Iv{z4>tE&jRceB0B&Yh_!WaHg`QLKL^u{*an`{feWXj*IUcRuEPlj+bw|WKH zEmnVN{GjRh1JaI?wcl4blL{Xcibm?sR)dfs&m!S zkLrnFmiXzU?8lP>oaftIGSm9WnLvZ%5Kv%hyZ{AfR>jB}{xUT!;Y{vG0YdtSj?Sg; zO@@4abMdVH%2`}vMa9hOGGj#2L}J?bu^MPKqN^{#gE2fdUJ!U19}Xgd!iH02ZBR1> ze^T=!PXcwOQC;WpW+84ZDDJZu6iem zm%EYh(Z3#7F!Yk7yDHFFOXMEm$N`mHDLl-Dgm4nw+xUe%W^mV|73X8lH@oTEMfX-? z_Ux>*lDp%bFEI<8#gM;W6uxSegN-O89)~)&Su<%b7Ba;ye*a*^xF_m)36VN@m4rZ| zeGY^+;+Q)xJYQa(jt$?wbz(Fu&(O*DzSKFrUBKQ%Locrlz226kR@o6>JJFzgQyUC{ zUFRE~3@To$RU=a(YhnjxU2$=7KP7+UtejV2t}VPgzV$!uvg|%m2)LN#`+YiKBMe*< z@qIJXG8B8*MC3xn)3p%Xje#P0zL zk#E+I*h>MS;VYL|{yx)?LZh=4G`?g@tbP!h|XR-yr6Hwq^5cIWR~TNuyqo zQsjwI9S@t0?K}1T4%J2p-woDBl8D>+TJ+}&11YJ@eZI97Nu%$9rwb0H(OTJr`1r&0 z?eyZ*Ct&6>Wn$^J!}+9vuV)(4&Df$xqU4ylb5&g~yl8gEB~O@*RYg=n3T$1w!m7i9 z>Uop7*5XVCyz{(66k`4cN`kyHGjSk8Y2aY%ZIsIm=wNir)Dn2}amZ`;d2K#GI1BJe z_7drn_0`>Vf&vi$8=-dVfY(pw?S@YcBHOd@w&bibGEu+Hb& zw)msU!W()-X!1UiMnmD!CIse}hz|S2D2oS_ntUGethL@j8U89C8`)d|2r4rJT@f@% zd1hwCvI=a5E#bj;w@5J z0k(?v;dl8aB&Rto-<*YMa}+2;Glq{BSQ3R9E!|H8Kk(7%?}UbHuTZ(Jr-g7kR@Nyl zC5^?7>=c@$jA-x_?AK*&PIEqfV-=!C!5B$$$t&CMtc z=MUIs&9RPRlKy56>6cgRrUim`dbU-TB0X;5CJqY<09ahNR85uLFw$W`|GAA%c05rt z1-cWVdkKK3c`}qAx!|l_v*cW#*^6Us2griHA*%jvW)Vl{LR=(Jq#Ryq7 z?a1(S?t8_O%BA9*%0Djk3h7?&PvlT_bysdsi>f~TEEU%xm~pNxJhET3SIsd#%51*}_64~o}UDkJe7RG zM~COHhGej?#9YIF*>9E@hf=ZLygxHhTR~OAHI6}-~gz_E|VE{N7(gS zR(7uC4&i60Ea%BG?*7bBZR&kfQEaE@aCW^KnZ&d8k%yzQsx3iCJi_`K>+{(y-|Cc% z@0!0zw&^lUcisw#l?V>MQ&0GRx1B>xL}h@b$)A=<^>>snikTOOc7&!5??d@PFSIui zQ|vwbxB~$k*yIK~0AmnAXuoujxkvxkVt$()_HE}BnC^NG{^WJqOFtK&3j&+Nlnq~@i68vB=3Ow{40$tNUYQJyHma`@-!)7ET~Ox ztgANrGIlfNr{Vg9fR2cw9!*>!?y}a(lji?WoJTKjOyg37J(A$1g$ZR^G zB!O+d7}(33%rU#N@!rn)4`8&&KKvBkINv@9H4;`@j^>`XVmdRXGA;*)rq+>S7&9J6 z*yu)mPlz>&hNZ$c@A0hdBSOH&RpAAt&R9nN6yogn1fxeKM`Ppczn_+)e5sx0bI8R{ zeY5~Xn_6{1*A?UOcKrEaHTqtCBEWBR^URt^^l@jFF(P^XjPzvYjpluwl0bw90`X1L z7y%6na^Ly^hHk3k0Q;|K6Cs1UTO!9L4Grq+Dcm@X8|lE@x&pgJ;#AR7j|7Hq3k~fs zLII>lY3Y_Bj1HwNzb8kiuaMb5q_x(h3paciSufkZ3=cfpC?xC9`DoFMP(JHIakv3Y z3NTu3!?xNSa(X$#Y}xbyV_0ZNb&`de{iS4OT+N>@q@ZS;|#^|8cL8*vuyr zaBLZ!x4iKCI@yU&gkZ#`y!T!;PL&7ZIR-kEA|DJ(pgs_cwqLrUYkoJedh~rT=$_U9 z`-e~H3x&afG@|_^lWHLVX@jLG%OyPe^8We8;Bh*}FA^V>^?a0HV9F)zHhRnh>$DRN zVIY5bc%(}15_#m~uPJX#t@OLwaG=!O(L2ozqnz1jL8bChR+4z@!uRxNZ8}?@jB#lH zM-LlhA8M*>Q}TOB-#Bsgt%4PF+|YLUn#Jsq@`Ph^?5L9*1MTd*v%N-2(6jkq|3W8C zM;{5qM@QM(6!s@lBQ~xjMMRc55ImMeN8xj2RiPrUeCpCZli$w2hm^4oVgd3r^_=@1 zMhCAx6TtY+oyE%k^X;_Of1Bs;F}nxIdab;kJIM0JW|9~oK-mbtp|9C^JI{V;QbIDK zcwI?+yQ_40xTA%2A|Ldz+z&JC2y^fAznCEm^jiMj;fKJVUqh;YRt6zzyg`0~q4)Ze z@bJ2e$AB&+(2nhcz6kzPCK&2l{S+~MAz1oj8g7Ce82VI0igx>Mo3^wQ?GpD%>JTSa zjNgU8j|#hGLq<}0e{d|&%h|)TKrNb_Ht!-C$ZQ1;Os%RVky{<4glF!{sUNGOGGf9u zdFB$D0rb@c(v>AH?p?Tn_&sb*x!r19!T!ONDUpl?QX{e1ZV@{0Mn_v!+`Rw>cuI*E z#i9DcaboA);e>L%PmMf+`0%))nC8Id{?Didi-sdsO)Rqr;oBMAS`(=X1(Nhgy(<0Y zchmH&x~&CHj7H{5{IYVRaTc(DnBucf;|)4`aJ|)ax>?Nqkh#lkjm_9T)gkFSfUej7;GE55J68&3UMk8=# zcOgw4;bv!_wVCqPtdyL|#aEIWkJ7@FF{;lCvS}GVx2n`qoqyk`ayxprX^22gc3Lrg zfsPgr@C(a1rT>lBUSfx7pIXmQYe(~-yI{VQzIBPjf5$n zo`cBdL`mO@+xPs0j0)sOEkjzBrppAhzVq(?rEA`UtKD)HRrDw{h@kv5ZCSHSt+p@h z=QjPW-pD3Xrb&T^?MkMu&YYn`(W0#X_mUIqZb41-eXF;$Gd(?$^2_M+QV_ss$zA8- z(F^9FgH-q0L|X}(E!LrTvgnwBv?4=b^%rc+WZ>+s?Tvh!Jvq%Zyyl5f2uW zp|yOBsCWB3g_5&89Cy{AqjA#q(pmcZXKENuK9&sh5hqafCh&MHJF%9QD~2tlK7tX<@Rbe$sf?5# zPhbY<3-T{PQ5ygAfuF!L0WaU#OKW`tCDc?J|W!ubMs@rhN{$knHjN+f2PvrTTUy7U31>E2GM&>$ucKjxJw9xud-lnq-wwNP@Bu#j_jrvi z!#x5YCV{U{O-kxozLbp33ui@e$5Z$-ED9`DXF06 z-7If4lJ=rgI5`Yy&b#dV)%>ihqwTCyegb~znT9^FfNTog^F5jLkA|(SMQu=CT#;vC zxU$Ne{8=LsR=Z!>T`6}jr1ZK=wWM_tfWX^==C|%?pZ$U_Uk!!Uss7!P;KL-gS|?NW z!g>@!Idt?O`(e)h_c93zu_Kd)6PJnB<`^(e=2aH$F+i0isn$HF8%4J) zTLe@f)={|#v+O1Z?sC;6X&d9bWncWYNs5bV%`_UeI4kZZnBs0Mh`cRz8EcU{|SM$r( zT#fqXdh*`q$UW8Hk-nE54&nkh|5C}Chxc~&?zNLB?cxU?_H|vSC(_l;DXoR<_{dsH zm&Azc^w8o#0jOA{`FHbU1>*~IWM#l~-P>j~IAoKaEEjyQC{0K6F+c|uzc;u?wNN2J zn<481>$u|86Epj8%YmQTmnhepj6Fvc5D4-s0VoXzk`i<9Gx5lB9beHERVcR_H!1LN z1u$)~Z(Z{$q7T={5pgouJ9YfjeTRIpwzGrt8s9V?xX-A<;bwHqjc<& zq*TH+%JyxLR{bhcU(!yju;vZ-rt~YiAzNRwoY2#B-rzsM6UVWTipE7jGt6iAf1BZD z%4buQh+mcyzAjrvtHLKdrCCSmRyYm>Y99@$<<3ziufirvZgaQbCtX?`4X#Jjt-R$qexULZt9p{O>` z;ycGeCIOqMQ~zYBPl=L~ZHTtA9VPFqu`!Y?oUTqbXoD04{(6@;0A4liGz2Sv)>bl-9sF-mn=(wzDlpVpAQo873O#?)v2 zFB9!ZZGnw_#n}fj20W;BTlvPU5t(zqXqcXO7lpI+v~SxQ@wcKLoE6AjgIzDh!;Zo| zmjZ5z=h!bU-+{|&&oxGN;rn16h|JuwhJ(%}7ttAtmIOm?=Ugp`QOXK=2yt;SIrAKu z#<1WnCI$CCqa}~sps^FCrxq}yS$_cOemsRPf7@FxY%}5Ln6-LW2~lD07OTX6Q13qm+!JTK!4s<-s9 zkzLZ0$_h%p2iz3LCPI6prZytfFT00{Ggx3;B_n^An7Pl{T?3i%f5ZdOc!@{<7Ahox z;tOs3qgKfUz79xbeuTbC5L*xK(nsdJkNdF=WQaNmZtX&hS9alPa^a)LyWr=)4Ca)- zh!|^bWxEEdf-(|9+n3akivUC0o-QbF0ACOk6qHIv?2ps~62hZ%H!aEkVP4$tqf2Ij z2X>b_nJ zHTE=wwZLp=Bj^H4_v5k@M38@q#Q4grj?Hf1V<@s?mo?#w;8;t#EUIjK@Kx~LqTzvS z#^;+oc7NH*j(xHt!D=MaE4Kw-jJs-fa>9d{T(PiAmdI@5=T*ZUOJc*GhxY@?9G$_J z=3?uPm;%sVg?f%&x-lmKJUPqc39`s75U>V0&Sx1#Wb`Ns|a6fDbF_cW>6P0hl~g_>fF}K!S5B zBQvXi9WcquY`ip)%hgN3rK`{=8zmEMRN)gD>gECsMv{Z-)WK)i_u6A%)%qm|U`O*q z@OR>JwE<4OBEY=8fUYU>CAFk;jvxs@t>5#XO2ax!qoo2R&GotgT@sg+HpG$&{B^$HK=noFJ$Mbr?_np6>?tuhJCQD8Lrut3lDaVyHHDH=h7>v7Du}>B z)ifx>XITcn)4sBzhPT_Vy(a8-P21-V|f>vIGc}Fdb ze)p&zgR03!FoIp*?k{?Algz^$SDN>;R{~VvP4e9-`kxjKno78fdoH-{f6j`@=>fdO zD7JP8Z;0$Kv<>lu(P+W zokW9_JR#pi0gO7se(~yQGKg*RoIVktsGdd~q?xWr7>-^>`5Lbw!EDJeShlrgGB#nS zoM!wrq1n}w9Fw11J-Of9B>ZajHQ2WFd0gz~cQ~nP9_#-c zU*&sR=0afPq@$CDu<7V`EvVgS_b4IYcUI+vwu1HY`t|6ZW?ia1%me41s`oz$W{?}X zGREOyMb=?QeG2?DXH#I$K_`mj%jYwh(1)L^V5}F~o0vu20~$(6;b0H610vt%6^Uza zS>kjQWFydQcwWwPMKN*7q^ea3hPVXs`4{mjLI6rBtoTNSfF9aiyLS%2TmYN#WNlv` zeHj$Cz3*grLt?4NHfLMdO3W*;=p|J*Ed221sHLK{+ZHqc6#6ENGxO8t2r<0~Xq$4h= z8SChPvX~!Onv1lqR6s%CTFDa;;hK-+KP(I7DV=KIZF=eNKJ$uT(MM#~nssNl!knAz z^s&f2Qu^@0t)$?m_Tb$dk?3;cEmb!sYc#M_>+X-wZpK=J6fa*RSX|70-otbI@v+)8 zH(J}TTWWf=jA?9yIRv~>8&_bBnUSZ7^bWJ=%kvACn>>N?i4Q0F0v*r zh+m_oT51wo9ljZzLufw<$p@!Ex+2*f!tl_E@$@E{^{q`u&!w!e=&Xvs5+(bMEr3W( z)z22Nk<`a3EdKiu6a}y1rD`RDw$2t0;ou?UA?uEoN_vEIP$g&qgCq4%b&eK;sMGs? zxm|oEvvxt)RyKvI^!+hP2s(o1lP(7<&bRL9JEGDiG-Xq9w8%AE1 znGN?%E=?L84I3%n`PN7LZv5J}S|8^-K_(C_JA`+$4=-9ZIIXm={{c1(IQ{t!;l}_W z1D-NS!P_FxL?_~0{MlMT{89ecY8>Ze78VRkA|nPre&WZ(McRqEn^MDIKm;%pZgM}< zeMBTR)iV;Y6>(NU3n)`M$w97rnXX+zGzwg$R0y0}?Id=6@BMD0jRlo`W9Lcjm42|u z3X?nflVz3Wqlul##^uU>AL_FBN*_uPjPM}1E0V14Q3GzdKXzw-Os3HWeu|&RqWKR8 z+~M*b(KPlY5bXW>#msc3*GhqO`WL#EH(myUMupCn*K7Bq_hC^--<`eTW)N$qlqYrv z94AO#Zg)T3F)o6=XP27=N94JB)elZl{nLQzTHf&;(enM2?FNV6=g@oHF0TRNBid)b z&`aUxtdNasCs9|YSITB`m>`YdRUSoV&F1<+h|PoWY>ZF|=yJ=^ChT?VY%BDVCNjp@ z2Xn{NFkQxf9e08XyYw=a$P7uX-TGUbC74|%MpRBtF0}ZTdyBFn+xmP(xr;<@Q)wJ1 z`}MPjWX_-~)SZwW@NxYQY+9F1hKe=2pfmvVS^rf{C)-6RQ`sUZAwd>PoPEv-^s9Qe zzg0RYY-Ge71HLBut0lfCJrCd;Jgv6KWQJ6}o!uSk&i=aHE2Z&jLHA+sz`asfzfd8| z2B6Mb?nw=4vB6a_JL}oIy51O1&KTn-(VL>xU2X)HOMu4o(x9wJ*49kQtAv*F25baj z02oV0jpB>x5+RF2A|(G@A+%QY)B>39RRW99qiAD)V80i_^yg+$`BF3%F{2hpUQGV| z6e(c!yn05sWNno(b4VZ^^MTL)+368ZCU5qmAGd^@M}n&s-ON>ro2610@SC(dVB36u z49|S^dwl&XU%4T2!@ZYvFB0H`)I5l!rpZe~S2Ib9V78ii;3E+E-`T@0?gK?tByw;* z*VGZcASd*=F1pbn=mQ}~G%UgB*F}oGVgp-D*xhi2u8x|zd~tHLn~>4os2l!1@QAar zq;l`Br11}rD@210M#$vP>=IrK8goe&L0lK-P)g=?=YI>s|_WKNc z9uI@3WVk$g5Hpnk+G~pz^HWph3_1UF>e$#=wuT|==YlF9{ZTKD?6-H%s=nj=HH}<9 z$9WHG-l_4YQw7)EuE$G(|bn$3wi%v6lHHQiU(fy2w#susUNfPi^7AhnpU|{9^UWp z7P55GrD;N6{_gc?Gem>BmrN^fjP)D(blAK|8thRR8Xh&pEpWZ8q=SWS&_ zH)%b=wb&>*)x!d_<+V#ZYAsf*4d5(hG8 z!8|$|mQsrS**l zSDzeZ4o(xqlG_qwJm#Y|sQnZQBIB6^@8|-_5}OHEw4s9yT1|gUn#Y9CkcxG<&8GwT za^oD;(DV$jk@@6c=cUp@oxNT&enq8g#RX0Kb_F(zij+oOb?pl%ckO?c5&bBM66f?{ zP={MHggxVyQ#&7Km|Hi3Jf~B74c}b>ulapE8>00@O(~fNn?EeC+p_8QVGi=ztM-vx zD=;VUMOaaM;P6CpC1GLUu*=1Z2L*A8GNFA@(qr_)Bfyq=k>6u~eGh;Vd~j8mjSdtW z?>M$gNv$IiU)Zc-3SbSZ3W6!aP41lpa}W_vCh&|HqGT}`BPERbc&>$2vFsjw^Po#t zk7+XtgF*XGdz@TK7i!(*5oWp!g401f-LHppccP;FgheJ?(hvw6Jwn6bF3LbSxZn6x zZ0B(2#OK-$tkUc7%%oUJT&78<^W)MP-g zO?wl=(HXjtd;vci=w<9j-`Rm*z+wCfe{Q+)!=wPBGEtQ51#|@};Rj>7au2NqSo4!Z ze|0pQWYwMPr}q^7!R^K5YPcr=g2Z^o34f{X@+*TL;geo!ATX#~ymUq__t(ojFslJk zRK;3ubBHWU4aJpA4aL@wCSk^>Fc?zb9J0qGo{bvyHZ<&1KEnun%}zv?w^2_Vp<_mLV!_VAwSk?Ke;OWELPb+jN9G7Xjqw$7 zL8)4vqKT>q?y{I0qqBjLiJ-$1Ke9olG{14nR$k0c4F>|V9;)DKBw7h zq1C0o^z$5KMdBa-@<^>-<<(2M1!X3J3Bt0U@?sf2pM7c4FFg8V(UKuGxCKB3%&QG( zxCwbmKU!kb;`<9ud-Ml&TS<*R)IU$IVb`bkEM~{PLwRa6va^@Mg!3~z(4#51Yjm&j z<+9tSRZx1FW4PQ`YS*D3P3x?5R(T2U?-RlVn{}_@I_cke(wSP6Q}+Q0d%L?#NR^ca zIEx+H_r0~MFJrgb4ndA6Gh!}xAy<7nF`L)CHcjK)RpZx{CJ|0>1e zMTMG$TJLL%$q+oaf~0Q5{1CZ}T~^`p+@Z^4u++DH`ZKn{=&2B@XMBipV z?1jm#CjmXNuwzRRL$rIG8z12rD(tK4^OqMmNh8$+PS0bvx0o0j`lkP`l8F}I|6jCD zX!GK6JvE;hH6qM*i)&Osdkk~GS^%o`9R+I+_G@2?vH7eglzWg7I0Nxi0q4po$LcWQ zTeHf|CZdU$;v<$St3O~ekg70@g;MzQe3fp&d}A=M&N7>AG^qm-zQ(G>pk(h+Vvs+_ zUggZ1?D%Q&P`qpf(GceuEyub>9`_(I$$CgYL7iok*Fh^(@47z*L4o+$<;P#P3Ps6s zz`l^!L;UQA~9gObj&5go?lBGQN)K|M)d16`o!+PcX* zlN&}w8ij}L@;__iF=%`ZLLapHyG7N{-c^!{E5JmxMSI3e;s@mW7gM=j4wul$-p<*( zg3RqA1`v+LS(9@iA0t1CfAHbMu#n^e%QbM}2VOm}ij|*g&efe228Rux2c~cn>@nb) zw9I)`K=DZaw=;x?nu7{=CdM)i@saPcgpUnqiXv z6n0N;VJUK-_jN5WnS>((`t-tVj0Td#{CZ3%4gc)7DE&>Dkfbz2Fh?+@#A)hpHS%t1 zZ1_sxlGZpQC^SnL(xaM50|-g^YFOJZ6u>$o{^$s< zvCxx!t*{+mW9}DEQU^Mp(xPpjY1sD;-97Po4Sck$+FbJ%wn-WfF|$ww&>V1U9)$OODh59CU$h8nqNSP-Me)v%GAhjtzI_gY?LL)PToG3;u(#)V?(TqdFBzqSXO%RqS(i zx*~)sqAUZCEdj26$#^PO9Z|nM+G=kWdfa#fUoHQqr} z*0?N9Ap8=GD7NUnL$*H~?%N8!lQrt&U1c1LOpo?S) z;oWYsRw_w6#X{<1?IT!8MB2t|+f?x^wNne>zyR%6vlH9l z+Wvr$88KiUC;Pj*sLnLSQx!mlpZSG&P@N=OQ!BE0w`juV-PAH;0S)rH-EhJ!^W!8YM^zw?D2hj-kKF z@jw@YvK-5V#af;FH<(~3-9$oOxt*EB1<@mX+(IR~&brWY}Z}V<&`e!Ah>CTTcv(-yiZ>_v%j@^|3yJ0v)s-mGH zA9?%zKl!(HMlU{bCvkv+G%hD-VDz3=_`~1v3gtfPH)v#p9pcI+V7rqgo|b>@C{_&+j1+Yu*5 z?cu-p7K5k+BzJY6Wc#*8XY6qzMkd&fefjQ5hM4I8aGk-Sr`YCk31E|WX{ zn;*vUdvyP2rliE8W__il*kWD1IDfN~M@Dxcxx4B!TP{czd)CHJ%hB=Fm^UYO|E)pBQNk`V1s3uD&~#QoZ7{&1 zPN29JcW5b6+#P}xcXuyt1&UiJR-EFl#U;2)DAwW{v}kdc;DI~;x#zs?^Ui#;yR+Zy z7IYLpVfl%p>$~XKzuz-ZH!f_Z7O0U<%cKb5*x(A~vQEc3wZS->za@hh+BUHZlBw*z zlj2~a;bLsg$JnczL-~KZtQ5g^ z>vk`ponuk{8Jn>E0^1&K3=0>p z_NqO_7XYBXES#JvALq)Pp13nkM{Sh3`>m65{q~|h{|Z-pJGtlCT~%eg0}J(aangRX z`UzDU6n4)hSR0s_C9F-tZo<46w7*(k>ncU=Q(Pd}DU2L7=?6%RrsKgP~Ko&%(&w&8X=dFJzNEQXxg2_)AUey8L zIcx(aB`gyi7gbQ|B}BZqXe&|my6j&i5>Og)(1#$)=Ot74xV-YBL?H;D!ZI&kkvMH$ z%v&TAf{u816E#iy>*3p3i~jOJkIcqzHvr4z!{6h4IH)AG=XI zZ2ex7r(J)Ae*~nr zOHj!cGc8juC{;Qw8x}F_u);{dx}DSzle@z0y4DZNVQ$j)dh&ih-SC{(#kcRF!);G8 zYo=(Q;z|wHBW~`u4%61rUp+6nMfTaOqT1uu`f)(?4Hc{yK2a#pT6-@}Lw#KNR)d#Z zpff^aqKbz=$<%0c)*_o&xs;Q*-r;xkD#jOiuA18^-wouC?7T4BAgx`+uKoG>uT4?j zdhvB-XRmn|`+WmPZgDV`2H{>>L?dlI%F zZ!CJOjY`hKI*tzd?vjp^=HQCUNC%J;kTL9aMNlZp7jQ*1ONy`kjB&5U%H#U+p=3n$ z8%w92Uac8P)@RAFo4B~Il@%4KTg1ej*DLXqmMy)w_`;@)YPl7#37IJD1p%GRcp-iC zgKeF6;-R3`iH~63qED=xoM?l}DH|_mK35m?eQ60Ur^%_=B?8NoFi0}){6fFb`srz4 z_-R^7POL9b3}wwL&zQ-MYs60x!}(~2qhQ-aUf-bnJe2IFbG-wI`@b5bn= z8s`VX2y>Ul@)@Ra$!crncRKMyA7@%QTl4u0K8-CEr%F({y$Id5TB`mA_Z6DlrX#W_ z364R-ldVZpl(H;>p@c9A!FbYF+gulJkg6AJY;mZX`!coy1#+io*!G*~`he~&tFNtvdV{vQU>LMZwF^Js*^hmj}9F}Ngk?QM3+z{N`BdS)1u z%Yo3a58!EB@PHgMnDVEpXU6*}7CKE#4<#Ob&d|bgqqp_ZbF$y`n4BBKvR7WdeaBDz{42p{t_+U3Kycafwq&@1;h3)CoxVA*NlTny&FyJpb{(ya-Pm9`{slFifYr>|U4E%1(1)(HT$L z_Z!26y3$ZJOTj5>xIRDYrsl-}J0-K${U=s?JXef+c+g$e9XiZ~8g1t=_kEy%6wlbM=f6f%-(1m!vK5`tH-~RroEGbnJ5~9sRu;;9 z`qIbmln++pdWRxTf1uiYSY=1+2x$U@VL)<i%VEX{n>15M%etFqPkPG!v1)&qCZbFTepesIB#hL-LpNMho*{1&WpNFe4=g17K!(U-(sDTcHCq3F>T%b!v~pT?kq!xo4zA0O?6`= za$`njl1CPqN%wq8Wq-%UKMg} z2@+*yRer~M{UWdxDdsjxcre|{n^m;V^a_%2882Jt)Hs#oNqs@~E@j{ii?;rfJg$#I6+=Tak-=ZQnZx@_eD3g=v+O zG_4jY+zK;VUnu@_kdk_P;$X=c!;?vo@E};^Ec<{i(bRZN{BH&+3)cIp(5IrBkWsMa zLB6?4hgR4l&5!9;@gA|onV(F2ob3gwf@%Yt{CE++IzJ@+6cH-^6$=dKHu(({59<@d zWl@QuOJrPFZnj{j)%&PjP749Jy>#pUbR2q*GPy?UIXe52<|SFmdg?ThpDpZN>pFi$ zzN)G0S~J%|T}TV~b5f>TRYAAPW?7=4be(zhZlwg`$%5BGYqUl1;p)i|Bf-P>*bdg! zmY)#u@Dc=?(|<=MnJvx56o0dsV`J9jn1#*G8nvBq+nQdTHX_+RAOHBbvs5*dREq3w zMC5MN(>2E;-KKcE6M}fB3(&QGgktH*o60*?rZD4xZ&IJ}K?%U<5 z5Z(3MyKFWSFjZe>{bklvFwV&8M-bxD#RxZ#4Ge0nY{jYhwwy03E2|}J^)uaVES-H; z!yF=+*)V8rjk^`dY#AFH`_}HDuL7%8U0IoxG1OTq#APvaVl1?i_EJMzo9Rzw)(-(& znTCW#NrZ|n95mavettRgzDECva8)ya--5M2KolGUyl_e9G|;exkCH7nwG$a-JJVpU!nZuiKx zm{u*usX^|Y!$eF0TpYq%QSPAgiN#W?j&3wOj)gx2I_I2$PwdZX&Milni`r2-uNbHB zm%Q_W%TT=Er)?W7J0poBzU#~zPwUiIvF0y*3Uv=M4pg}AH!nk)-&4NiQ9PO-g#2$0 zny}_hR|QDuA>4&rThR{e|A-C9aX+jZvzF}YyT>btdc^o|x+`#}`_EKs7M*e(4nCkQ z3K<+62&SM-285&lT9uTPZT|gs*LY1xLRz9D1iU5Ta@dzJZQYj$cgv{te)Id|eJ8?wUq8~aF zvXB!NP!c}+a80)8aO+etq`h zvC+>YgNs`%CLT80Ol)ay8Qv&!=JG-?%w1>ne6`qfYaMJgL8Nv4&&@#&Dy z+!Fv30w0GPQsp{?OdzNFvoc^&wx4LDvwk&n4h8$ai<~3O9RDOg*GuF3MiG2`FSlLe z@cPCOtK{2P>g}~C$=yFO2(?Q85e1y_Ob%^v3$LW7v_9QpCd4-9tK4IbdXP%%bkAYb z#?zbw%+FH`vNz52`h2&*IN!(pf>OnMi*m#5nwOX7aP{v`Hf;&Kdsq%XLHJLg4F}~q zaq2@Y~+x8qLnDk z7KI|!1j#?|-GAwgs06DgRgxEq+GXX}Q+YdgR}|NA_rA}UQUA)g6ur9bxp*}504k{$BK1x--Ut=$nEv(*I>}14G69c$_jpJ3t?5A_4<3Y%Q}1ha&}%8 zf>?wIKs1jKl{WYHI8Dx;fBAOvE_q>OX$NhNY zrOxz;euJv=Qe&rRGOCj%Ri(0%W*%NxhgSaN54b?qv)~WNFVt*0bL$FSr&;*C*5j1n zoF%BhutdwRh4UveeD~w#09+>)iENs6p*+`nfC^sm&FzNPD8)V)kezLj7qQ|S!@NwMbnzVG?f6gJ87J@JBd=xaaE55RNb z-N%R{KUZnd0ICb8-)TS6r8-_5EAPfO7(xMQoJwD6dJo_DgeB51)CYUbhSF5H&;#EA z_^%Y^!;XIniNAis!kLfOpTvOIW(=iO97EoI35>!9s z`ccVe6tlA;CA76-KNQ-G$0Z=`6+p`Ar$%yUP><&hiYH&qTEDXfrAWa4fUa&qcUZ3z zEQr!r(x04&0Xyunu`qX*+a;>ER z9@~_oQBT4ig!H(de$!tgUJN~QEyNp%#o^J!#^Y{#i`rNP-w#du+zQ;U_f>Mv?TiED z4^|FIgSU_m!(LApZEDx^N!SdMf=?GgnKS_>Ga>~?{#uJE{;#d;eef3Lp5BT@eR%M~ zvNu9|YJXuPk(Mj){`Zcn>Vv4+*xmG_&uJnB-oz7+m&E*o#=cA*-mZj;Dc+I)7m+$N zs07gu$j;a&dJ6tvR!GUVtcNO3?O zfH}R*LL7fH@VyeZsW_4Z7`jA+oB_@RSZ!`z*2-Gxf*8^})^8KdHOcAIW^HOz|1UVYj!D2Y}&g~>%Vw4Nfjmxu}+qNFw zpl!mCAgmMO@$$1=S& zO)#}6>o1!mtlp*W5l2-qfKxyXFR^|*OA9Va5A7M!wawGEu8{7QCBFr0HmDoE+79t~ zMs6%KozrrpaVg@=KT@;d$Bec^yEU~i&)2)gxFxmT><D_d4lw`ix&QcVG=F z+1=gGmp|-D*d!bYm7o-N*+i|^E-ry$5c~RU3&ADB0y})#EnT6ru?40{bvKby^=PGMoTvHg;7FPH~Shvh? zx<7Io2e-kS_VkzJ&asrgGB6b8GddJiG$`i^ZUvYTs{QQkkT>>}Q_}KZo^R;{b|E!0 zlqK4$dQ0QnA}Bz^gbUp6(A*CszUGj<$+1fCm=VdbX0IX4V9#ooqlDT8YZcK5Q8xEc zrP%m;`tmNgf~n7F^kT8^g<_(B)FdiL{6bjj+uJ{s&nIa{!CQ0c0tBEVxK2;LND3@* z?w#2P`pXL}$nEhL4XOQ6Mrwv|8oKSsg$wugQbs}CL+~$W2rP!f~-fzZUH@) zJ4}zX{H_`7=Gm>zCN8V9rUCUfIHgVvVH|LKU}3Iyg{S%p{J2nR|0mwdFPFo{*h#$h z^w4VFDnp#wT*{=E-TaX`{d4nmjrH~v%710hM!m1O?xPs1(@`b50r&eMFZ#3lpeIs? zaIjjA<1cS-ukyRT*Aea4GvvcMNYFx8`Rg+MX7aT>_t9gwKkkJcpoYu>+qty%b*XP1 z|91Q_Dn|5iHtc+{7IR{dqQVg18ERl-td_ok9D{<7G+g}c-`n&>U`6aVN`pNFv4S(P zPrS^e?J@3gFV+>l)B#Qw;u^7V~}pM7BDSb?D4YT zS(d>w&NJxv^hBK)=2zUYNbU2=tnmH;f_%?x&zW6^m=pUf{qc?{+I)yXezI*rKyQk`60J+W zSzdTSiII=VEuZ)4DIFRyf5=* zS%Vay8P~+o=;>a~ti|{L4GI{oS#l`{IQfz$V#?L=2P#ph|&bdlitWH-+0pBD4 zi+FFK*B179$7y2q4{c)W51Coo*S*A_xKfT5KN_MGzcBLY70{@LJmFo>S;w|7Q(XKE z9cKQts_~1Yim<+?vNjAgFGa56oTK9(Pk*0RWO#{u{M%^<<)_v{`Lk|zz?9(J zN*Ze*ps)<6ikc)Fic#@1BxaVMt*C^iuBg`x4ShKqhEJ(MeAHw0Fxp;%&cOmQ<81AZ z1BIk~fMQVIQrMFizaNUUfE4MT;k$kr3P9>~@BKhRRyG5n*hk6`=Ct5CMX{JA*`9@m zdto0<7AG-WLhH3J6}6B7Ii8z=^>K{0fM%IeTN~ORpYW@^l8I`j-=u0+8=jM^B!}gr zU0s>XtI^m)<%4t=eNh<4Mk%UYH<>Th%n7d5u)b^${%E#6t!kEq{g#zF^__mj$w10q z>1EEslH3skC!J zZ_X~ipsZq&Z!^cB_w^-Uc6H;0W^s)1FigPErgkcSYrv+Y?jPnhw$rI*%-vAcd5`OW zKlRo>$VNGvtCfi0FodT3cH|HrPv68{_7So1`la)*tj%}g^&ivg`=IBYkaX|cyG7sH z>y|owufKK2lK+cNC+>401bHAbUP#aNlPs#%AEI%PXZovhKIiJfBBkJ!N8Dq^hV86s6C$%p~>!tYT zzgzx7fz+OP&-iReYY@pl>34oQ5W@vl-#3&OP8~4jFHZO0w|f8JYj=cAD=TzZK}WYhp5S*pa2DJr?b{m{j<>Us1<0RZp0n_?uloO ze-@F;;USB6`&$}8POxv3qnY8IYWb9{tBk|b@DEkU$h5*!mO5y04N{&Mcr*3$J|$Uw zKgd8bLmW7v*^n-;xrxLQ`V6i?a(Vc3JKw-wI0Daan1{8K@>_rx53ENbZbLp)o6rO4 zQagu|(`x~3IL1dcso3zZ+7X}e%kF@8CHX83x{e7RKLIL(xFd{vLQ`7wnR9`zGe}JQ z_=E=hi9Z^X8Y~K;P`&{B==tz4m&$se=N5NbEL9;mCBiRQRYg_7f<$`82b7N_?W8PL z3mm!|77ej6=_0>!nG{J3Q0L@1nsWw@W9$ z+eEN|bEpj9bAEf8ExKCsW=}Y^8|7c$oqRB(YL>tpqEE^zs_zD`Ko!yDtx!*e0fcsF z>_kaF{Qb5!EdquPf7*3+eB$_AZt z&Rosw@^xB~t$=d}{64{ruiB4GBNFL*;~kQtPd$fN=J(Q_cfD?9;#KM!3VPq46ZIp3 zaQF%c1iox=TCBS{X^Nf9JkIER$qzn0&-#im-YFke?*To8`Gm}pOq;w=hbUM1l`w7q zD8}F(vHFxMYxZ;d+y@JE@R847*9yJz69v?1@Ow5ba-fRNQ8j|xQ zT=Y5*w#O*oT0mkj#*1YS_5soopeRO{`P>c!mO8sd_5kB{Pfi3{`DGrN7E_`6;!b@T zPnrR`)^P`x$_GR$Ab<U$Im8y|8tC@S=q&C0-#c4T)liTM*5G%)JiF#z?>W!s)COWi+6_>J zFUVU;-S!i1L}_0mALAF-@b5}%!xqeMO4TJmJeYTO`;z^nbhD%T1#rfSM{I+7014N} z!n%?Y(V&Nd7hy!d{EHB^?nWa!n2edGUSK7nI9;M4zG-+FKXauWi7$@nbic)_LFFm2 zDR9y&9mrD(3;} ziZoKWD2|1Bk&N1KQEn_eF9MyFWl`s#n5X2fsM(-)(v|rxIoCH9>%HINoKiS zxiez6=Ove>%K6mzyNuH+iq>!?G2+adjvjcA9;1e}nkejrjW0iGDH$6_ZCe?bIZ0oh zy@{b3$i4C~TtN1c#|X^#IispI=EVjr))?jqxEfUVE|mv)x6=aaYK&VQ+$7<9A_Uj1 zHtzNu1ngXyZ=y2Lpw4P>O&l~rbcMA-AJ%JqM`$EikAzXVBSm`RdW&{2Y=Ew1oYk=?}HF2iKXU`rRHp+RUjw4d727wjex>i$nR%(! zhvj8jaV*Vi{rtp5I~otay-nZ?xP6GMXtK>?O0(*6TSrc)PyPEbV3u0zAB749x?G-? z>nt*ciM}q^2f%y14q%gp>{+^h_zoZir~rl(Q=qy6(tvgsI5Kh;(X~G{De#oA3jA1H z4B9%~RT5&UIgb9BN%2T%1I8=BOsd&d;F-lmR?&ml7L2omYRhIB4XF! z0crPcs0-1TP**qK<`SFQqt$QN|EEtwix(F_3dZ2tk6-Nhh!_odXt~MiLl{$2QXXJC z0!j=clwL>ZQ~l%PuMCJ*U5$f{dnmZ_JS}TtSr)-UBhsu%C;(DrJ7ZPkp_aTvJV_Rk z8S+n&N8G7UJzTpl&c^%LK@Sc&hK20>+M4yYvK@pZ9`V+!dGN$fkwa4wS(D;!YR!gE zD81>u3=-f@*#)fMt??b!`usJek6keDYOi0=@$oFxRR{Q71Ha1jbHjitL?INTc*nmIevqb^MHcMHLG~WR>L7k52S_ zOW$RbR&=(HKh8Z(3Vq>THE6?lBsTM-s@Hz-x#*V92A9rvWY&gVc7?cBKOvwP!6D zo>{GWLVVN1Z{cATOMDH%4pqeO_s(PNw%{3oGt8`em7!=?Ibcqyn0jtQjdQ?nC(2QS(?Upp|;1( zhDiE9UqSWxFk?5>wvFJfI%GS)-rL*TvhsYRr2k$v znJTmYaSHix{V7=;Vfa)uER}_3JshW)Vd`!8pi%R`+VcaZeW;%w{A4m$pZrYNsojY1RAo2M)6I;{l_0%$Y_y#Q=$y z;dP=fl6e|*jqK(qC;<9-Q)&jA_fO=NIfy7t0P_8f;53fC!(gaQbN+rN7KvE8fQ!kw zfba@DWF9iuN#bOREC^i3AY_aRYDtB%>enh%+r-BGBBC_eME=sRq=Uc}qjQZJvaen^ zz4Sa?n1rOh+!b_wL`=727;-D@n4;Z@|t_*}S`)MYe zrHU-*Z|&tU3zxV;P917*>($^P|@hD0t!Q*f$<^1c;`*3UdZ=ycBw{1``D5QN@xZ* zXW@vF0&8)}x_w0`a-*=ps951sdpbMfo zqMy&01YG@*FRr^+rrCJ9AFexkI)*R!gaj>M56p1}m#OBYyZRj)&z<_L<*#4u39dfo zJv=X2Czf^~_4-Wph>CaF&)fwC)m}sDKwb!O1T2wv_pzpq)(cT_EN==rf*=3s3T{Da z4?J`Z1df|aA8$Nhxu4=~0IL35n86u!_-V2QU5*1QuD71}X~BfdJ&b=I{a`g3 zuWAL{V(8 z{5We0q!RSW#Q@n|V>8ymA7Qdrl9H3Nua^NQtTnEcc@&OjRz;F#t=#yNdQ;9aK5vNh zaLg^jPejnXz@NBy(wn<9Id|Hy2LXlU*V+4{5`w8u}-&uM(3H! zy#6P{Ib5zK3ImObRF=MBjEpQFIVFg#pEZyFcKk;EFhFOuRTt(2g{bBT ztdO)bpN;AJ0jR&!tHT>=?H2>;b7*S!J3BjZW>!{KsIHw#Ka_bloK`N7Yzjt`N~o_C z-w|*w)zW%K`F+0X`>sww*+3?k`h7x?u-w4LY=sip$Q4Imq)luhAR6LbshV}SYdPdh z^$RijFe^6|jYOv2bgn%ki?pR>GPij8txqzwINdAgtDCgTu7VyjriIxmYdhA>AW64= z%R-yIDgBu|W=-NWX!G0^4%En+v^0(T8L82Beeq&8yH8$9TD<<~Pt&Ir*2N7tI;_`Y z`p5tkr%P)|7IMl>*`wz+CAvV&6DCHmfVMNpnhc)&xKsNKr6zgRzI^vzVg7Sh%?Hq% z4yv%GK=>)ol-GelmyH|NAe(t4Hh;q{G2chbWgZ(qoTx6V&rEUo+$8lXCE&-|$)uMi z&go~um`3N^G(YXy8svPJznz*f<2{i~lEgYyP)Ry$jW{PmsF}=+FJ_%xmxx>$=rR6| z9FxL>VzST!r)EFL{3r+X+7&RjP2A%iI&t^GImu5vOt~nI!Cun|TX_mpGZyjz$_I=d5$n29JDSt@E zx?uASxG)B#P#&=XuEs8TL7iW!A_q`<56hB&kD)51!E=t$3`M4K*{JdSs%mvQ;3#iV z8H|Q>&FpxpfsXu@SRQq#3Zj&2*pqFob_HN*1GAEtJ$)~k0Z5QB_64}A-Y z@|dETAZGCX>ZLlJ=^(DBBB#1nY#X&%jvt@$Zqj zheu2>ngSv3ha@hL%UkvU$48_g5f?UOty|4xj!}wjc-ZH+F2B3?m|`sU#)K9)nbH|m z^SA$6{FuB&?Gm9G^}4lA6T^^u6jmU)L+xh(4sDfvBAq}u z&cDN-*pM@VJf-zk<}``|&5LHd=WBMJ+p!!Y4E-@=Oqj8nSDJ0<4uWS5{S z*@{Ilx85I_FaIn7AamIV&WjQ+x@$8gsD(U=f_A*gRc!6aKjYXqHZI)CgS^y_4zVuG z4&s0TksZzM5DS)5YFGRAfl)1QuHdzwd@4t}ts|}hiK*@YQZ_xTH~D-H9-ZgCeusAw zH+|UK2TlN?Ag@nVOGsg(LV!vDf2(!r1o?^;oWk+wUJ;b;;?GADXP8mQf**`1Q`I}r ziY1{F(4z|;Za&1WVYki^7%N)xLTL8WEFS2pgd?1^y`I0VkpG?2!9uoj;m0*tgx$C^ zy8;)!$$!%amsVKD5VyI0=k(RNoON;foS|L_(vr`ra7nQ4&k(eB+CO~g3qI(zJt$Eb_% ziC67fH`pzHV<7i~M_jU3mx_>^m(R;4a#Dq6n4n900#>oADnu54053H@*`9iPh4z+#d}>QUKY&#iiuxl?i>FG zb7gFQj(3VfXM2{U?Q%nO(yL4C4DJtq>Rj*67W&t8SXB+-x#&UMuFmden4kGAZ)_Co zP2|`e1e^!mmAZ(tkZX=S#8K~`@9$g2=X9#U?gO%%$~*I6@Eg9KDeZlyJP6aZXICYF z!(7PxFxDmranHHZ0&)y#UibYUDQkFubtALpx@0m@1f;h7EEy4S+TzxXxDJm_DW-wY z4NCxjQ)@-K>L4^-S*#`$=_3_Q$5g!}$&NHmvVeU6D>~D)6F~~TuUHI=7OXy@6Huk2 zkmC9`a!BDCrWBn=6a>?#I^;Eo%iv9g23dAMxbg%sYk~T)P7_hR$uH~g;L(E_YuzRT z!Ize|UlLl!lN%o%c9nw`QQ_3ywP-(&-q?P{XkW@F130Ex&HvbaPPF6<#Dvi%TtCJ# zm2KSbz8+XdN>f}AgEZBUlm%S=rb|5P-&Nv)2Z8gL8XpDf(NMC%KTqriFD$j5_Kct_ z!QW2&qBJ1dkkeEoA`Oi1*yvPrzI!#EbNdpn5jTqkk1F8nNOo^1B`)@F^7j!ZSQK{a zSm13YWIaHSZp{kqYDqH6@A|*R46#}{R!6hSW_A^w2HtCN8@l>t)eWl!B<#V%Rr7|9 z^7C|h-@rQc^**Q#P}4Az0RskPX7F!Um;ZAC^n7V3?dj@He|f2F4|)Id&wuQ%yN+{Q z)azb>Ec}fTJZiFS>3lL9v0Oz_4_s|A335FODI{r##Y}5oqt9{I8H=<6Xj0>?npQ+7StWFwBZx^VF#dArylJ0=Ghl0aV*OI2{8$9c)Ie$@z>kk!w8wcb4$e5=eUDdtUh~3k^`-# z-=I%;L=1bv4t)eTn7P5nwQkCSYrX-GtFQYzhu?%Ve!78tA)&V&T1bS6(2J`gFR@HE zxFxdMaNs~=pp{}Na=T|Wkf_9jZ)RxBnD?+~?)j8r^@Obqwk`oy=1Y?yVyTPNE@HjVPOWk~wBdGARef9Pv$2Ks%~Uq}c-H!`KCN>Cwhd5j|{FKusL%Cz}@na}A_ zWwCa*M>f>pC_M77=aR(J9rmX~Ue++rK%kQ!U~&mJ$&oHMlqDLa?)6v%dP#w)8e9&k z3~K*8qg@pyPEXf*yYH)W;?9xVv~WN!CaQ*_cL=E;#+96M2L#*@A2}r8b;tVu8hi(v z1pX9uT`r3Q2|y(W!n9zNKY6F>?P0->kFDii$1t+(^rw?v^3bDzUqp#Lx|{xAg00_x zSNS0g#5Anm6{!lF-&pbZIPkV~04J#EiI$WYHH_PS1HojzQiu+_^E&K3)bh$XyK>s6 z=mOP5g{+6Al51q#WAS;Ma&K1HY$$Ecn-7z<7z|hzZ;Wth#MVxoQM}?G%6#Bs0)dFm zG+_F*tJ+XtvrYSBUQ4BE)e&xOJk))$iv!b#0dFZ??2gdI))gOX5bb&iZw>_JV{+F3@Ga%&*|IfnmLz zLHS*M#7Yl;nIw!xYEGC^q2p+*YoRN+!X}jOe|#>mvS{1>z8}5ZXxpyW&>B1SQXj!I zsdVaKLYF!9fu;WZuLrA;I)CW0W`XkyDVy(!jq#rp8RDkDjSmGPew}pB_Q+pMMhwr3 zZ|}f2^V*3H1)6isW+Ayp588Jjj*I2CuV(&-44Py5N*hj)9+;;`!Kl<)$SX2ZujicL zS*P-%n@6lr>9Gy<`AXkqht}fat1N#Kc(G3GLyg}JvFfGw|ipC#$21-to7aXQ_rUlHm?mso&M?rEZV z%O{(DtWEx3(-R@7lahqS=}Hc0nSe=vL!@G~fEbA{DyiIN!Igwq-{5hLwoV?uv78ov4Xh2yVj{|rUrxo&Uu;ofs zl)UC8uR`Q^s~z#l8m#G07pe%-$e|B-9P)exDI?#XR7?aterhelQBc}wz`$3iJVO$pc6K6mRp;sQ=sU8Q!V@@*%N4)EM~?Fe4@(qTNJ} z!h=vRMwyz?TP#AYLB@s$&g;OuDJW&Uoy(g>-Qn2_b(8@Lm+DOuu=~o>kxCK){LCdU zl$`0d znG?A)p1+Kji_>v&axQOJNsw0=B`i-0tv9!-`I+GAl)($FV0_O3O%S)==;;x6Xj(%T zdx;;Z&Iti(Sc}X2jgbK=av6wHx>n)gYAllHxG}|sTT4Z^Y|+=hN-QY^7D7VX#z|rL z!+Bl_?u_rio{S&C|Il9;Q8kP+GUbX$&tr|+KJv*BPX`w_oSH)FSv` zM5rijoj39hl343BrW`Wm3E`G#kUimDNi0-fb(@-=lgsg$91n} z%}F!Gxfa8HQ1`RK4cD+%53Wr;S~dM!%udY*%DaDm8L(|+?&Y^(F2nyd*7SG7DPTTj zay}^v{9h`O-d`E z%5YH{_$EE3zA2j_(Y%bcWKLejI=wCegNAa~&^N7)N(ItzDgI^cS$t1|EAjV%Xhn!{ z8onX#0~k?eQ~?DWNuJG%Dp(*nGHoAQKfpS@QGE?4;oqEPavtF;2;~_-Q7ZUy%s(7@ zu(1ESZtl+fitdw|6Kkt(|3lYGG=R92Xjn}{$u*E0s<-D}RmjHu0F3yNyuGGM@@3^# zWhMWiPM-CS9%@Fqwy3jf#_JZBu%bngb%qMSX;mB4nCTgDNxo-M*}B{G`Yu;8wxKLfI$JLSYw!mncU@> zILFJAZ1)bbw;PK_wWjs{-)E4G$3=+Q5Lb$Q+>c;Uc$&Xw=w9IG2bGC)?wDaI;?INH zm1aK5jma~@3eKxR5}faz0#>|#jU0Zr`zFd0n#iFrj#_wZn6#i8%(e1J_v&!A6aNOX z;#>0KTXj(C!V6nc{LtZ$27G_?L#VAXqLU~3*`i$MbMz$leiTw8)FwPn6cY7H67!(; zMB?I2lKXgqU-b6314V=VWX(ga^JrDh4Sf%e)MQ-#c0Qokt;En5!RU~vG1|nc%=e=8 zpndkKg80UY7PG@gL7(y}V-dQ_%8n*iwestq&lq@@QNTbUKQk{J(#@QBX4O-!c!ZaxT<4aww6z8_wXb9HU)WRB$$k+yekiAq@k z6)WdEOlW%Iy83NoSgW6XRX3R@n5RsLU?c7(h=Ws4`)m%|tCDTyV&*;CXsI)Dg|vyf zpysVWnAqW(@wE``P}^8@A@K!}ME5g6L!0|TPJ!jcd+x=97}iN{DG>Qt#7j#14Y@XH z!&i3sbk=}qq0C;_g*mz9qsTTw*E^|4rQH5giCFmlLD&8z?xS;TOXTf(%5VdmUm%fhk5Cg5nvHy+_OsF;7zTI)Dc-FAQbyBttKgP2(+ ztmH`snpg1VT}v8w==iCQo^TB@OvrhcX+8U<1>bQ4w2(`_SCCBBQ!?XrYBQ^y_Tp;~ zA^+XNo|U78__jX>Qjw@i5zRsdu-dmM_M9A8Bm)2{cJnI#@sc%LuDOt^4C!97{wHG3 zEYLV%D4=p8BXrgO*SfL) zB;M2`F&bvUB7s{B7d$S9YT_2xsvvh;#>z;aSi&B;t}sjl-HcpQqQm$kvn6A{^$L-W zJc>vGedVhZYZmAp)CWzD)SfEGmr~d99aGx9Wasi@Pqkh(-RG%Xok^u*x5baJnn~4R z9~M;5Ea^D6Z}*MoVy{mG>;GKvd%b{|0Is5F#syym4;2n>psm7REqlQ2@5=0m(jVwJ zX}1rL9YbC>sPtJOxf;$e7}p?`WXj4=xBbv7Hz(ZbZt~izTxt7^!^P7v4`pj)Jn{s0 zr_g{8@R*O67f#GF1^g~2wbIKHAM<1wLU4yh@nH1xXqTze^eY!Ds)8~nUPXh&gGcg?l6UgYnW#SLNW@in8r8@!?ycxVgY%ycS|$2 zjJ(GohkZ-C1BE>@`?Cyf!%;2wvy@f%XAQuP52y8gl3#R}WrvEZPHUu9ls{qRD;5BL zW?APaBoS$Q)AmWWpWVpxoc25o97@*ZIW6Nnz`O3DV! z($KM;KG=SCEfk14Zq@OcT9OhO>s%#>dfAp_Jn+G!QCd}&dVIwYGndK6oiZ&fp#5aB zwtkbD7@qj%hNS^CNFX14YZ$Jk@N|e1o9yISwfnOTZUIZP#?l#P%w3K$H|CeaLykDiI->HVIjw1dv%?Uj- zHUc}@yveR5j1@c$yBpmoAZm!M^-5932~RT|P&_}0N3t|{GjmY zLC@68xXkj!m!1Q5jTFU`IEFqS`~4o*-DVuVV|*ewyl9zA)_z6hU*-vCsoXEH^5fhI zwf!0&iUZ<8KM@25-jJIVd32h*xfPk4IcDfSQ{PW%{8IbRvGgB=@ZT-Bz`c-!zai{Y zJ$zn!a zl!+(StO9S`FSuyMh(ihH0GuR#n1bBXN|LIt8jxirC{I+Cu3>YM@Y5z2#_;6H+9Dep1%R20^xy_ldVuW7UMMapXnMsm67#hpfsc!VeOt0P#!08_DFk z8_$)js~|vSfJu~%^G|YHCvyT{g4cSjF}yW((Nw-IrpBVDSnRI(S$R_R;fMPfq%49L z5_ZEv?IS-8z_f-f;CBE|;$x`jdJVsCQ(zKn5la{Or#pp))HMn@sX~Z&#Bbgwz$4-d zA-`-lvN|L+mvT{X*8;&8aS~t7Q#!~nSFyI@>IRTWa}v0})gkWN`pB7fsvWAhtlsZs zjwq>&DCHEZ4&e57wSznA&TRFOSf}OD;(^0DhG-AnmHj=1<@;I3@3FmPJ$ zp#6vna+84IYG2HQ$y~upanAi;jkAI>SH_ub|14HXXEIZtveC4GWJSVnn=D&1pWZ>jcv=LNx>F)+K}-f@;fp2ONQ3g;ctSV);{*Ok zRU%4B<+5j#s2kIGbcc(ngc(O|=hm~xlb&RCh~IeCY~8{~u(~Kf@)KJbGxF-Q${;PE zW01K)J!uQDFj$lJ&=eS)Jhby`vQ(J1Bf4D%9&&KVJn@)7Pv&#b>zUkj)756c9OEJx zqduxz#NRU1Tvd+dz5uGRi`ZHn;xxZlkK1Rm@U5B&ocYX8r;Eak7phF)&+<82(I}UC zqtF!J(0RyH$S{T-9dUWiI#cLg*bh@uVO~km_|kQNLr-$(UzD8YOE@MEbXHW1_=Rqd z_wp@;tn|M8wqS9{6!@lcg-K@%>##q;sv}i^!p8>p9!Gig>LIVXmJ2^&Ev+h(r4&2v zt?+_MZW6WP=4oJD&g_UFU1UTT^}h$yic5L;*!iExCzVhNu?QsP`omuOR6{Y8M_35} zCSV}5<61*e%aBd5?48CTRqE2>|7CIYyYb=Fyi&@V3#G z_@~Vsb}8L~Nu-oxoe0$sAGtLvXveh2S8u+|wAhot{l=`WitVP7BbMCS3&RB%JiZ{Q zU3|nKHbS)cCu}^tcJ;H%H&#;?zu6B=FHE2#=fU}ofVx{~Ih^OF_zSyapfwI2BBH^R zr|?U>hMK>w<-G9R7L-(L0*46s}xi6+bJUM2LI$zQ*O=*lGbh zfaxGlVgU8D@D+%>WXG(7Xy=YBzByr^RpFu1`QlVk zwhUsdIuM08xhYwGd)r23luOg!E2?B5=1$~7#!g1A0jm3?;FgH^f0b) zOO|~UC4J_k4Nzp!*;3_iwMx|w)0uCBxFm)U$3K_*O_-3UJxEG^?eyA_Fcjw8&!ami zCqw&|g83|f4~T2B>)s$uZgDNm*r0IP!+yyBlqhCSzDJ!;fnk5{E_)YHZTE^y%6atB z{Gbm)vBJ`)ii|`2u3t8b%U%ia(6G@_VO`gsM3ETROeKA8pZ{b@lRzsMQCBQLW33so zu5eGl%Jsy4x6aK8WJd>^DYf*hmAZpDtvWBg{je#4HmS0*2orVNcC6wvM=`dfG_O1a zCkXwp#cD4BCy7OSJrcsQ~ zTQZgUnqO@@Jf@Vz^*wE>yy&%6(l2_esWF zfcvwomv`_0Ooo}5pc+8={MZ4@D|1D}1CXzG6JQ=eBRmP$GjeYi5$#Wnu7F`)cFWjM zBF&%D&o|#uycXmtFPKUS2h+*ib_Pu(U9HXcuO)Sj`2WW77LERq)LOvslXorYj|&B# zJpu{=b=*eIz(Z%^9C`zcA(qZl1o;xAf7t_0fiE_I>;$$cnQuf;{kA^QlMG@`QWDh* zjCYSc8muBLWgTz+I1Ujo@)M*IRVNxH&C%eI0beY7(T|@+Bn~y1?zbHTuYNw=3@IBP zg(c6CK(wqD1f;*4Y-Fnv|2Q-83lI9uwZW%-d}&A1>xX`5w#iDc9S*3W2|H@n-|l$i zw1Gs=q^S~;Gn!Q-NBh$XuoU6!*=e>@c#bNZ{(_V>OtpmX@`9IPK^~H%n z%{e1}_7u6TowR$P6tWv-JK4>go}>aAm~=e#5GrQ_xDx+p{5I8=x#)vwRv#FI*xBCwu4cY9U_6V>-jYqzbk4rtIMM*RjmQ)f0w%&S~<;RZR9 z_wQW@X$!Orx}MIw^Pminxi5hYQ&0Iw)y*krD1tP9eHS{M(^sq}?e&v1_?>LiI>R-D zt+LRNv~)k>q&#WAT6oO#js~$YiFzc7)NsW7;8XsO1NzH9Kp!X!x@#5mHWcaGv~>aB zx+9vw?cNG|gA^TqWr>G)*koC__xkl3HUz-^pxLQMgN@SM5ie&syEz zmDW7g!6uyUDu?&Cs@_;QTQb#Ld)G^LLjQhhr4s=*MfRLLNO{5etJ%UX)O2M>F@491 z6Bz781b+^OXZRdBK1VE{bu@AQElaDk;jl|@5m~&YYkfGDBej5ei1@lD2~6kPwY>ph zT#NDfoO@S4YgV%5=SKn$yaDGm!=x4DTkCk5#SOoWZnJ(g)?~lI;V-0OB4j3}rlCt< zDf3OAk$G6B9mFv_JV(Z(p!iTp|LW`~zC`h6A05jYE_HJQIo{?ye?Q%KW3jE1ui|%u zn8*#)Fh!08;}=ezmxL*YWfi6r1Kh(_L|3lR6CJmDSH)+lNm24N|02l$yh>L`O-P8# zd?u81r1P?#bErRJJ3m-*=|Inyb!KkZm=vC{7g20-XLiMS@hi1-QGIt*c%w>|o*RlL z7qk#;E~73luwUGvIeHsi@4g5MSXW~laTRc=Qb^2@$b`Y!4}3FB>jwyZbRURXH3H)2uXcYa%l~V2=28lj+gEIPZ!``Oy$nkww|mrz=ukb#OA}e`7w;0LKjtoZhQ2+ z6gLkxGNJ2Wb9kCxXy6XY;zZ%4ag?uR)JL1Onhmx@3bEqAFO0|ADz_$c_Ybw$7{e?* z-Jii3d?dK3Uy&x5gV*``J*|TM=llm4%(l1sWI4|W%bsZ9)<1%Ft%={el`hz)DU5TI zcs}PaS*5}oaErbCp>sR7Jy|VfhV28zypBo!{U|y1L`Ic;A$&>^`o%igrPe!Hc>(|) z%E|1XbGV5*FV{$WSi^WU1XRPwb>W@QOdly`2|+}bj)vPw*KKxLe}74o@f^bsD7Xc& zac9Z4KCgEvefgP!cBZX0+DmQj!>3dXS%PPT<0lUK5t8#m>5IKIn0H=EZN;uiZ!G5C zmkSodp}{CbHcQx40AN+0PT>=m!G%PVk{d@VjaiIg;sm!&=YUlA>*@ z)_@M@w;<~#7Kc3Z+c_Uw1JmZeovrqm7~Pe2#W<(EqJS4<=FS5IQcW5U#RxqN)s3$nNw}K@i`br? zj2d_CQwxWw)!Il}G25?gn4;rkOhgaZ!1!heX!iuR^Q-gIWeYR_3ZL3C2rB`n;xcqJR?i z83SwCPD|g~z2oJPIft}x(%$dZ2GWX9x~)9=PMGKknX3Kt_lx48>JLM3iAx)~E@KU1 zfP{vn&-yAJF99IpwhJt?BeMSJYzVlBLwG_TxSwL=VUbxX{jznIy^CDw2sw@d7kW0! zf&0y3b%=Ul!?qBj8Gr0K%QEx$j-otaM373HfRKeMgc6`o8(gUVX8Up3=VAv6_QMP$^_s7H$y`F%O2E^FNqC72S78o$jRG_6f13?Z6zUNIzPF(8;Mz}1>2}sw@KfEQdg|3JB5omkK;#qB$Z;~zRj zBHQ0DUUz2<0P|f*^55hPP5_^15En=TU>ErvB=0|gtuq>iMG;t0(>K(kZ{76*LMqpR z<&I4}B4X4;5>kyz#BMS#$XHzmF7H^>%+zWtnaM~C75>@;0=%ny1g&YQ^L`Wuf}_ebB-_A{WmE?ba}VX?=@cU z@i%HXA0)9MA2t2Gj`4xYjB$VTc@PvOWfyXI)@s!BB77p-D-4z8oG&+hujuLRvq)lY z4ttSt07~Jj?E)OF2Nwb4pNVS^DtYi5{;Fk=y>rAl5HbYZpc>po@57!;b7v5ejz=kz z>9dOeV2zmq&uWd>+D5m9t!UPHCxz?fPWsR5!XGZ2T!nqLp3$n^k4FOz;PQ{o}jG z8mLv6i&4m;2IZ4|PE0pe9PE4^?{rp+=~>ZrNzlvtM5sAn#=2Cj6v{I(7T>+L@-Co-}hC zAeb3_>Gqf(NVzoKvuOT1*J?X7Nx2+D!Jb5uV7OWX6#m&?xng>tIOtK_xX<)^o{wMl zDVS3BMTlCGb9=K`qlPP!biaBX3PgzUbbE^zv=$UfiRd?;B4(!E%ix+PaW+8SP6rkH z=Y`)c?cQEsS2P7Pg|(Spv865tkN0r4Q;Fj@)t-LM%x??p?M2L1*+kgEAz@^H zPDU1iK-;JkmA}=I%*NLaw#Wr%1q8eC@t0d1hn(W!Me# zCCPAaDfm}D%IZ(P#!eQ_lE(E)m2lgr-rTuS!Eu~79@opC?dDbM z!!F1hTnHDX4N0+n?8E6N@8@gc^G=mTbvQd{tL&re9S?ZTgM}?KFDCR0W4qWKNTW^X znpoRB@!9(t`ZZKTab%r8hpr0En@NG&u1rb29d`V+t8QM&XyB@`3t5zdRLv4; zE9V_STuPHLw!?|fZdWSK80IXyH)COEJfRTuL}j2}7SU~Erd<&EiT#9i)L1M_(;I|x zH0u|PfL?-gKlrKWX3xH}V9H~jEb9H3sGm+{Z?e7}Kf!SE%Y~Pv*!V-YikFjTKVd8O z?sT(ulEHnAcKYpWP_o^n_L%>8)WqF!8Y0hKiTUpr>Dc##kz_9)HY!P@tGm1x+6r3j zf2l1z-2ne7zsRpFi?aDZv))ll$73S<8Tj~nIUM8Ry2CK5;A#xiDC0HTCcL~?>j>_)NL4F^`C|J_8T0E zPEVZUE-ep5dwu^AO=2;}-S|*f0qC#x;TZ+08{#?d?c)C|<*$=p|0Bfv*Npc!$WN&f z{ne?B)02XWGz4Sj(Y~I_hJ~h7`Ur^e%KCsmm^_`$EFfU6=lJkaS7t+R0jNWnT4#{X zP-}fB927~JOcW8wm7=FVozc|~xQl2(OcGvrE4p9DmdMfv0GL+Qnu0eSZcx*LlWLC! z+Q`C=vlWAK)&&+)GUYPwyy5-;Z(6Um>2)p&odp9EoUEC|n4yx*Zi(pVm?Ym>7;DVm zTTu3_w!CUISjpy&>w=XMP2yh)et0V))jnjEPT(1I>XOMkU8Liv`Sd+}CqbR2qTO6v z+5+Fj66^tYWL+SSh`5)K)$ozybYr&&niBnCK5|>rV$(K7i>>ll-Z=H$)tT_0r*1O# zs6=0C#_>ued$cCkEcyHlLZ1-5Vz%t0mZl~tf5@70LJ@TC(;MdHU(_+Ul z%eBU|6NS|iLDU2*^~*;hjYHzpH52AnNPr@J(I97I4z8oSTx_|~rWdRtJ(J`MYA=Vl zwqIf35ih!|`|C-BNGTiDnlz~vrCbc>yjfs^+;?`^U@aQHaB6wm#6DX}g5R8mx6$_l zPtr|x#{+s~ge_aSmClYpN$;s}u|YpVNh~KDP8obcI%bH$lB+=t);((q+d0KSdMXk( zgT8wFS*9EOwR0(T=zOvJ(S6f@Yz8>}LP%J4j48u*Uk4}uAnb;g~g zYz61WG|Ib<}HPg1Jv>}ho7=H)CONp#-$o7SmKHb<5rB#pQf-k z$~gCo1iu*dPJE$gvjqPN7)L~;>5!M>hu%=~eGN`v;|to^V7S%}58u;{Dd5 znM~IbU>HB71rx^HOFsN2Dy9#!wInza_Xdl@N_L0UopWJ$wd0TEmHm1f(D?q&Wf|#8 zO!;`0ycH_6s<7}6h_5!*5Kx#c_xlB#$nL=9cKqj5K6fK4QA6{O@w!*r7h#phdK;xu zulxU@7fg{q{(FQL?R5`?Ass_+zdpT;;p+M!qYQchC?~YHSfJ-ML`)N15R`ut$wI11 zCB70_9oE&OWp*(#2!~3#<3P|4-pL7C$#%M=+@PY}Y_PS;2vyjV*hrxd`j4Gs4%$xw z@HnYHOCqpuRXvZjRC?-|9Km}5DId^x{V9fbcRe%guvoYAXh zPw8+l{d{YkdRxYUD)*6Yp+xmBuB+qQ^ySk`v&k4gJ<(b6u3GuOvXu{d8PUDP^%R?L zYbO8?=s)ZEFvV?ZE>X4=gr4Xv5TJ7xKzx1! znKticOnqhHZo8mCJ1^oqqn{$XY88Gv-s-Sa-D;*{#?{*2;?gr*a53Yhv>n5IW2>WN z;D)Acwacp{(F$#Qbl}8y#Y0Ab?XzP_&Ch5C_`u_UFmB6uE9Xa3=fc@~N9{|DNPycX z5Hsen`{>w^iqw^Ho6nAsDVtM)xXbKv@(1t{0}2Y$%(o9uJ_ z$g_rxrkRhv-)0%iY}ei5mMN^C?~Zj1U&Z;Y7r_H2*3756D-Cy3?kXfIZ9h{1hVEJo zGr*ICn}8zfYEK%BH(-@E9G)55rEOk_hhJ`;FbPkBsVprhW)G(ny&!uf-|f@P>0}iM z=@~pU-ph%+&<1=RjCE1T>KwZeOUa`pTulzMhj3NNPjKw#Yx7%=k?wGw%|ea1yD~0# zXnr38aJ6L)igNkFX3}yWfsUl}0TIscB_2MA(G(XY0n}{%3jWeoeDFo(Gl?SC+0wv+ z&rjW2#@go1Tsut`n1lisF&Tg=WC|A7WUjKV<++jTp%w6AGhs3Sce-1^ik_*XJL)xq zg&ykf<49VD!b53lj$dz7gx$(suBce?VX7*~VW{YOiYPx229_^;f|v#l01RWYHJW$yjFQl#mbR2eCeh*cx#XS9@a)rRwn z4>{CCwI-%bs>IwhQgHt2o<iStI4Owqt z)A6n8DVZ$Tvq~Wf=CH5tzJm+wd-%ogIg-&cg`~PU%w%(NyqJJ)Xr4hz@}+c*xZCT| zO9p;sKn3vq2KX}tNs;`0S%*|73UuQ&kvEWIH%rhmyjQq60V1wKLZz4)b_rpcla>-H zkhmKApy)q{u`0LnuU|)n&5rOvQJP! z;UF1pcwG^%HO1zmmwJdV2(zVoE(dk`KM3wk_O&BUTqu^P;f>QAN~b2(9#VhI!$|4m zlZ0x7QeW8!B~}S@_;9;M>pfun?Zoe9w$k{^{Z$;mH&edhz|7h@<}29nj7ql5(p9gq zG*i9l6{YRR?yx0iL02;_K)ct*!y3b*FEO7u7=)Z(fyKa#(JI?7l&nvfpfliw!( z=|F4ZkA{ylFAEojyr?z5zREY!?&9G}?`l1@0k}M})Z49IK5txW<{mjPI^=!wwb~pR zT|Ofje-{W>dJ`{-SMR4!rEYZ?os02uu9t%c4cAvfLDy4lm4cksT-jQAQ|I+M`NA=v zlacu?xs2)CS72d^fFZE4)a!m3#FiJQu{Re+o{*A{c%ZM~{Ml1Yz3)?c*PI(%GczAO zi_RadJw(;0uM^t+@RGG^Q+=Xy-N=YZBk}3upZRs=WYqLfrem1Ai>LOlM}5$)3t5IS zg@S=#k4blKa2Lp8Wd3YSJ{&R5LzAed=}*F~CtPyMoCwunH)5tZUm1cR2$dow4R38Hc~Gu4u51;TCz7EBmi^N>^Uy%6N=A zS~R>K&qSvmVimu<%FQ|G!DtIYJbI4R_&RCR{wah&56uN3St1sO8|BM~80_ddt0NYI z?E@zj%7_1-^jpi4B>6Q!CUWlc%}0*H!}?8yH)H*1G%WldS*IQ{HZw6V6Wd&$^4}d? zrviIt)$?-G=*wq`35rTm2C)kUu|HB=;OJb;^QvErL`NnNBA&aHjry9j?~zbluTm92 zLj;)EC${M)gJNrjAi2KRGm!CWij7qz6wit8d%Nr7gx;d6kEPI}45a@}%#RQ$dIK#a z@(~8NniNXA=F1tiiR(Tg6IvxQC>rMvC%FKrk%^G~q|BPu%7X5ikcl{hN*_?9Vmm(Ueky#jPryl!7Gvn&qv$ATa z{fuNjZ6%ZRO1!zbIo*<3v3=t?sB*4)*S!EP~->$BO6|&D>(RwU)_8sB!&<4B# z#mjCx!-CtSh*2E$zMO)jofhIC=88kL%0uFJR<*BqfhGLT2}<&ea9Zb%Yq?kxb9zyS~X13!jEgPy!#0&hUMF&d*UqVN5+_k+C z>r3=A=9LJ)Ul5e;mvPA`aPnnZVxlR3t%2cdlcm=<4`okaIuGf7Y&n>sYKh)EdX z#rE!jRGCS@)ADdFY>BA$(h{Ak{Y1|9U@kZ(ga2%6d*;IhUl*!x|5^*&01wMD6Zs_#E~rED4t%_MR`-U;}k} z!!sJ*gr%;RhTT@L^lMifT48U3H%a{P_^+MHRfQ^8%(n0CH5tI13r6Dnf9urdL5^-T zfWG?Pt=O`kc_`MtN={8T?HUt5(C6G^ewheBJxFL4P6aUwao{EwQoG|%I{Rr~t16#N zmjD6yKFj(2HJk%HrVCwup2TlGd;|Ce&*IfAd?lDEdQ26*mk5%UX6RET3Q(hX9K9+; zpJ(_T_i?}23?WR!3?S2eQ0l+IF85ISH-e;%qXF$-LO^}>dVm;FZ*q^7`yuq5;!|-p z@;<;v0NFh9-jTfBuxpeETo<|m?Xl;|8fDK}_WOlC6%nc_mIby@w64vDOlS39HZ_#v zNt$GnF`G=c+xXpVL+@CrS)koACmv`SZhDY4t^R%URk;W+Bh7B2&mlo zOgAdNdJo^FEwJpS#D-y3Q2IJzTR??u3Lwvs=Y4Wjw6s+HTuZTJw47Sje`;2v-DQyi zyq}Te9)OfBRMqS3im9Kt2W@4@VHJfIjugC&Rh(%BTsea6`M=SywLP|!q|Sc#T!h@I zcGd^KRPxC_e3Zlb@saepAnxnYYy2xKGmTu~j|*>gdP0!yBSX6RY$=nR^YBuqb`IU< zL7Hs>Zeq?RTd{(@LY^29D~;fg-}2Sj!LezZ4ki_u&$AIk8&Bg^z)wk|a0Y;bEr!V| zM|}p#=wk6U7!GPOlQ|Sm40MoWx}b!!&D)#?#YET6yEZs8JExsnzFK@o~2eB3)Vj~ zTYrIDHm5}Uw)+?XH|#Bgk$EZBRi`c0&>|4x|7=~2$IM#C@)J2=bns~+mo)zPa)8}2 zWQ(0l^!6epdWwb*Y zXpIOf4|4(hQFDiw!w4LFEM5=rIKL<0ZN2xqn_sN%W=yORI%U)q+E$Vs+|EJ>ih|yq z-6BW>_~)T7w=Lei&_ndM*3G(+0FwJXx|#)hk5Lqld8mmRzglStwg-i*B%c=RjQ^sQ zg}Xp$;ktnI;z$oDH;$pByEGtSItUEcNc&>?=SK{GQH12|{$x8;Y#dKeg}FJsy-7IT z8K9u-`4E?E_x`cMJiRWhHF41g9k7`S+k1*kPR248R`PjUBRm|Bq4cWnSQkLrFY&qT zbRXcDs(>REF7e3E*tev_6d{P~Ksb`K!fU#?vlDU!~wV#rh|xb%O09 z5mh3{Xi-L=@4iuO3{j7)KLSSOxz7rN_U6%lJ%c_?FV=Hm_{|2*mD6{wCP)b&o1C(0 zo%(5iR)MEq{eGChs3L53I7S8k=u?|v@GIwkx&U<-ylMg1Lr*KfXW;dqL+oDT!iaC6 zN^dn&?`!ErJ3{Rjlh)e*1k|Wo=_gvN0{bWCV^ZCv)Gi1a5o{3&mD&?FywX$8AQddk zqJ|aQyXs~5HHIhvvFgA!!+EBpwm)>1ea0m9=+NgRj=myli6rv7+}8-ZDWh6(p3-M| z!$GDtwUCc-PYds~Yis}UF=kO$?BQOme+%4~pOf!bn7e?PdJ8u{QD}A_*(w{EvY~KkE6w$uA9TaKE@-^z+~oj=c~(egoZsRj_{Xol zU<%dJIPy?jRRv@E!zT}9*X1-7(`qwdDo5^`V!Aq;q@aw#Q^c;BT;TJJdk(r}m@iHa zCpATn*%vxnRK{{;CVrp0S3yFqaN|EQ4aXMS0TwGLTv%KEp&z6MZT8QDA+r5&0^7|1 z|8v=JUD<%VsXEr%9udTX|0Dd3{U?)J+YDLtHRHORR5JVtms#>m^EfC4NErM$`&elm zaJb7f%QENLxTdC3RD?K5#C@&=l}ZaNF!J(9IRLW(%nKljhmFET!=7@2mmf~bJeykrX1%{LCQYXg4ptOEtGO zyIl*9oIH^}Yc>9;OHtLlyQ1JCzCw$Fn=MU>DH~umK^*A&d*@_nYPt(0p47*A!NVXD zQiAgfsiNKVs+N+i+T=goZV5nsF(PA`7l&*mO<@ZP%lXPj3H^BmW~~BdnvUHY=2z{N zA*CrB>=cb&w>7!CvXkxr^IaeAy+%rj2u0T^LBX9%%;77hJQY3*+3ioh;MHBU)m4S0 z+kE1w{9GDS(J$q9f?h_5h{_H*CbKgKUi%1?%>(wC6+If+IomUrTilSOo?nb=^n7b5 zG2G-y0Z>Maa$4Gr^2LiKmq$V^sOHhV#)n)xrWJPOImC>2(L=bbGn1qb7G3+^szY&0 zC)sEIeCo`#1UypPjRqnxD++eP!9)7*_Vv#Sxvphgh>k-yp zXmh$5|2`W*?eGxc)St6%hKZ$T#6n%;q6>{PZ@DQ+9SUu*9GE05aHxq+0ueB(v|fWS zNd8M-m0+TIYFRswKf3mwY@Q$O{K-JlgR%*-SYpeW>90YSQk`!{$9ApFJ~XdprS4{9 zIuI1)>?H-4?n8jL*qQkzo;d$C{ll@XXKfE0XqzN9*up+S>{qkZcT#5aJ#;HAOe4A9 zRLXJ)R3|dhyVCbioCrdGf4E$io{}@y6!SZy)@Qqe@xs{TYXHC6NbT?M#loiYgM_%gvYcO57ekTCku+$F?s!?%KLC98O{wu2bPc&s%50Y>gZGQUe_keR3 zAiUiFVbRcsaY}wSN1?dijd5d{4a5qUU&8bTVsJ*_2grK%dl!Tqc8`x0x#LW~)suYQ z*Q3hD;$o7}leUjIBAzIIX#VkYvi3WOfT_p`%EL{_ZO3L(!#z+k2UCjZzg%=(s5t|Q z>$Ya#D)=m)GDUmBNxv%6M;g+^e4DjWq*688D+V^mx63iTtTMoj({>nxw{uz$2N|>n zc#m9Rg_#4uAi!FJoj&?iBYygd@k=;<%ezq1_^-D+dzO4RN)r}4KT6WX-j;)F6!Lzf zVthp)t)26D2{IJqzS1`L{k;!C8(e!~oJ zTGyJ-K#d!Lm6O2t>=T9qs8WL75({AZuAQKEgyAfCjT?LJ>j21t>z|MpFgIYMVR-c+ z)Tzk|wWyZw%3ys~2@D2}z5u#*E3RyB{eanxp_bSyP=NJA#U1=PY$Qr%mQ|m!w zAaP@;fX+6&YJ+QesPC^{cU_r6V(X;s=)DAK-5NOzPwO+Z#n67vRa1_JB#!S!wMsnn zw&ahWjFgGW8}M-q$uteJKeMNJu_UPJGE4|yU!^3H?5`<+*(NFveSu`ze)vm_!m$RU zWlw2F{I5Z|pMQ=16FTq@ldN~z-)sI|^c3hwQn#vDYzIPN7(uJxPREp();JE@>kv!_% zE(mh^#h6Ef!dC@{*DqJp{y)?9FX#~3fQEaKuYS_d3s+Nnz8^bJBSno;{BKmOi;QS- zsoejqOH?N6-$WZ4zj zX~e-rO_U?{($fkMqXyLq(63%s`l5#FO1Fw0O>HUJ$jhRz;w?tLf>q-(i`A3B+55}> ziEks71pZCQZdPtPtH3bK{cU#Q9E{P6JlSTI)v0vc5VX*hC?)JiuJLB6HK3nOkZ!pA0@az) zXEudPKYE*J@G{+ySnKv0^Km}m;^0f=OeMM`Qoiqiz3yI+ukC-|6HTQOd?O~jKP0db zKl}h+${DlDw-WLNW*QaBZFWq2R4wfP|a6$9V+ zGSNT4(IpAuhlNsA>R9%UvD>>$MDtU(fucmG%3_ii{MtzB;rR8-Lz-%R#j!g3`n#m% zyrUTQ?AC?bZ~}uRD=6WqM2(SPr2nEAO!&$#?q>>R@e^#(Gn((@j!%K(*1$;(d_%u0 zo6gip3x_lxw-QBxm6aj~jX^H3uHCOhZ-+o=DTh8-&BmbS! zuUFiAODd^vdW6(Aq_xlsP%SsY{oy|*ULO!#wrXkV)mL&S`K6~Hc?>bZ^IG&vS2z9V z_^au+nk0`Z0-#K8I~(^Z_i{-7K+Jv76`trxNVCy;dkw@5z_5L+YB4l zXTg>boA7?@b=nXelG^;h-`k`zl{0JW+hCe5+Na1rl`qwh^nDVTwVFcoQT~9X3TKuN zc+Nps_XZ7;kp`34_Hx1IrF2#y^Ay~i@I+5i2;kxbv|Vt)_}* z&Jo32^1rCWTr$ixP8B_M$&khmWJF{(bsqKMF3jxbN-odk2iXtHggKi4l)oO8X+o!e zSHxy=#O~9#jt%oH2Qnk(=K+df9&Z2}QSIcvvSicQn@iW-8X{~<4ln$F21>O{X3QSu zw`L19`p#ZEs{;|F5zJx6%x>X@M+LxWC{gfZYYR!YCyk|wydE``&785?zK;!(D&8xmAvkt<5??)v3kjzvB3JJgD8Na`RH~mkLoQ+OKj&#oiq49v4fq{cZjnFEd2`7uh@8^Q6`z-#?% zNd|1_&hZ(EU?V!yB*M`M9vSlYkaRQ}{V0{sh%La5LcW>xr^?xg+LBB>gNz@^chvsK zp8CCLncy||(fNH}i}%0Ha`El0jiNaYj7#30uFItd4ltjVJ#&RyfkuqxB3EnShNI#7 ze7~3Guk#f8O}XZf#@U5JuDK`p zs9d^1>LUe!XXa$k_%u-Hpc9>Tc{4MT9nN&?%+!}3TLkXRT%T@H;?kHUG^a@=u9j}8T-T0EwmL3s z_Fw_AU)M_c4pjfw5)2pPlswqq&gsj6qh$i~rk8p9&LWc%eJ^*K6H^m=Fx?8NcfS&6 zcf~8_TyyPl9V=un34a+Ib+b*qiC6Le`)!eg3&iR7MS_#!=F)|hbo)K`Y0?gVrLd2sGM;NNr+St3HY)7-fekRNL@A;$ zSa4h%Kvq_hnl^Ywzch9gOyob~>c=QxPewyUAD6V=9m4n#zPM;MqR955JnXzXuYk(T zj`ZW57uU3D1lVa)TJDpp5vYuazTSrD+!}0nyAIBF6xAyDYNc()e@+3(6AtPHoprN` z9de;!j;!M50RvP&@7_);9DkhlnEzSP@^?WpggMF`+Xih5T0Xmwkx{G>Bu^t}0m=={ zb|kD27d=Zq;+bC-fMs$me{xN(lgA#&@C6%}o~@jrbmlw`e}OhlVNcRS;l9n+L@flXHL4wCb_HG-GSdg2!$-zYC1?`rekRxKmCu~OQq z;9rkL6$Sa)1){I-l7)`5fOitNpao(uY0Z|}s*#j+De-4u5b4N5dQEZrDHoX4n=KGi zycv7opvr6xgSU#XJX3vZqWQH&Dr{Gk5jdY~XWPOg z`p>m`*HzWvtOCe4=MW=D5Rxr)#|Z2UkQXpz-C~Y!9UF8AHS4SWX7;x})8X~w2cwGj zLEb)qBBNW8sk+zusJfeymK}Cu6x6kKL`W?cNYn?=#Z?*A{oP7eSuo9?Q9KV@iT!Cv zECpr4rv77Fc=jdcUA70{GDy@ zDQi=6K(U)U7>=~KP6+tvQS>T$iy8I)l<^|BP*o6P9QK-4nBIA(xlk&u6AeD}N-5KY z8bEENRr3181C3F$oDlX7>Ag^!$CTtQCYbX<;ltHxj`4imb*2g*EX6K&E>t~wBz4ep z9v(gi9PRR4H|tNKS>Y%vj1a%{AoI)a?SVW?Afuc^tuSKN0GFpd0)y@>Um(A;D=(SgYhbHayfU~D3# z!ml)q;fdf~9TNf2vnT#xM_7w2#1(d4>!wa2%Fhm;n`I%P1c2Fa5(~f?1lJ^Hmyv1*0k3{;mzexJ5 z4TV&=M2-x$?MWQoCDHO6Hhl?;gxWY5a9xlv+U9ApMNWnwVs(zZf2F$3w_I)T{wRbil zvR;e73>h_&YdrK?TRgQ%TkRj9?a}F-^rSW9R*fI}e!C(1KFw#7%rX$bCHqYF!Asya zKuGASGKNgLEM-ew5w6;;+{l^XY(C%?ybq?# zW-mkURmTXzTjt{+;y|)w8XHx{lUe%ek}JuqXukC_GoY=V>u$K%x?3A5OIYgj$xHh7 zvUbiM3l|oue@RweqP1~)DGd$4Zat5UyRLZSOfTD0t_{GFy>Wi2|4t3Xf>NVc zGu6Z!*4(avDVE%TvBJ7i+t+(8a{z@W)XA>Jful3A-`FanTcsKxZz~T;#v6E%H6wgO zapFk<&qoSSU#g0iXd!SeSpXfB+a zUnB)a%QYb$?l#vBu6(RB-J;0QQtEW$6R&;7N?)a4_=Q2V$btV`#ZdR#z;~!wy4_ag z`MYC?G|_&<<-W_f+0NnD;m32c+{qMwZ-M~2``!CcxmNc|ATinU5|=)y#(B|Kf+C_F zWKr7liKMaIO>=?e#;!SSgouS(DmcW()hb74Z_4ro{t;g#L`2|m#zYu}hBCvDEKz56 zTm3tKDnLO2&L&&4Iqehu6%j0RG@_&{BT(F(UO12v8z?oZOHXmgn8En*-)SeEpn;zO!~z-6b+}DiN%qM|BMuNvz$n3!jult1Uax&d9pj3t5QR zCpU~xZqZMmH==QG)u-i&Yf^}JC|E7tn(+PVVqhPYQ-8BJV2SU3SqNCtRl_r*vmOUY zn<-jusAN0whhyzhkqX z?*2gT?Ee~#kzbab#t~h^6R0}uZVrM?SY$huwp6A|mA&hV$x_xz&hbkYT;V(;QJz79(j>idyTdYUnh1}hjuCi;Z#Fx7qg=f zJo0owHPw+q^;cO+CPn0fliC?A7T;+~TtR9O>BMplf_})d>MY_z5tzngAR^7i; z@%&99XO_EM1eSU?c-KkG+|^Qf695OhfF6^tW)UXjhGqwcNG(FD^M`-MljkWCdMsvV zV$NGo36z84-XW2wx-sb>Kt{1bhYqCqc&FYi>v1y|G>|3_oYlsB2~;zBwIrQX7uyV3cSFq z6c2$~)N)~+S+xn@1Z;ChlmZ-ZaDU#a@>@k&!b;q-wQkD3R$W<7WBWrfw4N&^n|(K))OIux?VrDJ;E$W6d&tKh*Rf zCzs&~M0RNjUS~5ihs?QUi1fMbYFIvcF7lC9+tNbdwhA2WiuCq0Zhhq)^b-;YS&!h5 zaS$Gi;b67#tM%11>W96WqZe5P3mIkI zVMA5e7E^mK^ZxC;_O%{TH@m%05%ln(>*^!W@`JD4H*Rry#-A>mu9lqUQvVfOVLx9q zJAtx|CKmXo6y&zliZ)XO`&sJKMwV01+E8 zXqsSh(gmIyG0c2vmu1zIElnj=ToW%FYbk2nFHts_6>b>(^c8r$!fk?V&fC(XtH%;bTL1puRsU;RQ9 z2Ez8}c718K>$k#3c|XSYwx3TNxZ+py&+BiHpP%=SU$2;rX>dO(&(DN9`QJj z3NU%Yfjh2G7XK92hU0UBN#uxk1N2P9SEK-@C6P-z!K6cr+M8`@#6JOXR4R9UmsYFU z@R&ZZnQc<3Lc4FK$oW=)e|OJ%2(EqC^%cXFl1S+LetE_K77Gq)=4Yvm9N*N-zv+VSTQZc z+cP=tpTFNMeb%^cw;?CVz3>`Nqt1wdzH9~&>x`1jyh{_1ScVwLP<~N8{JHxr{j$4tZGga(uxE|N5 z!dDLqc$%3RnINsO!t+SY-HqDQ;{VG6WL>Xk({`uN6X3l!=V)dwuj&AHxK9hZi-A>? zi8saOY8D#O0kP06ek-X6RGbvvpP{k^yRF~_V0_^kB^#D2~KQ(SilP4speiP zBhBnNbCh%Ax*e;sVYab!^C&q7T*nH+e?imy&0xxy_3@kG9@>+&MOj-S%Th~~fHctJ z7e(kZM3Z1|YY*62&EXeW3ckrdO`Lhux|pc~*CHkAOAa(WcccJRd5{ISq>AC#Gqhve zMmA?ZRFdB3zAB#DAsUf%U3s1nxs*fP9;fUmlo{DQ5TIh>04d281=Y-7DihYtH%6?z z-IIpDnv9BA&(ViAaL*@#$hdY2IA+p1!r=iQ4w5Np*0=isyVb%e7FiQnG_J$4DN;%! z-$c2WzTBWa@12D&#dWL#-DVbX@lTZ+(cu-E;rH_wf!CZk{MP1R0_AlYibK2vFn@H#&hb9^UwDtg*zk%KQs+&?FbUkh$E zjwFoV30`4BvTs9$`O{#M%Itt#tt7ZTU0e@_Pzg9uGoI!s_UXcQ1da1oed>Rf zyS{teZ6)mxo;t0UHMI5pvFOr%mwS=FTg3IB#EuAC5LsIgK?-5-u5G!}EWrr`>j8VS zN7Fiz|H7&%{;EW;w0VCDk6zfTf0nNJoIPZz+y?ZeuU{#+PW0rc1g3=V*Q2aacJl-6(}+0xuo9oa;r$kj9@Vz!T4(xeNH} zPMMpbUFs(>Ri7rzC%_+m-jj!gyPoNIjLeT!{j3-GJVd?(;3-$7wTp+ckVdK_h^c&^ z!ioO_uyST8j0b!tyJkd>8ql{B7VJ*|8@!be1DyKfnVh`ptZNM z9Mr=UHjQ4&4-^0D^cZ5{SF8Lnd(KxCiQRJ_1uWz~BqCm0X@C6iu=y@GwvS)fzIzam zX(ek@XzSs{l^NCZiQSJq;|+Wnz@%*nuL1a*>uQx4{B?SwgN#dLpl**m{ldLho~T)! zKqV_%9QL=C$e|wyM(9};#YuTuPrx8Ami~j!ELNwC$-no@(&1#iFzJ(}lG;ud)qmCM zt}pKQw$7#$`&Fv>47?Bibwft3iDp)+Yks#h-#4O=%*jpiX^i>v` z5s(?~=xB*<$CTM3i1NG&R6TSZA{CWngz5r?dMST+>X)Zs)_c-x|FGlSunMXczsyOh zNgnTjDt_n+!U%(w$8(`z$G=1{Ws92&`Z7imUe%|oPCYsM8u#KLkg- z9Vjky#i-WzbV#fB6CWOoupk_#yXBcQBz_g#K$u(xeQrwGp+p679c>eTEBa6Lc>Bk| zF--*Ey!=0HnDPg(?rrR_ck@{J;bJR6QF_wnmW@@hX_}OL&S#)}ujAmN*4y-#N>;bm zyQZ~YDa{mJ{G)+vnSw0blH?JvSRUw)1ndV&;B8HV?K9~lK&OR}gAX|K()pC)rBrf2 zcI(^UFDCjX<-wKh-et{+zBC`1r`(f`=t zsdJJ(`^B)LE%HVoN4Cjd&4O5SZluH*Jg4cr(TD`33u?c?PW6Td>QZt_6SDp^U+O*o zLr3G%!Xb1ke$fg`K^TV26w9oRyu`CCzA?;oAUM)EMiqU_dd(MgBfrnbR{e!;M`sRy zh4fvVrdB)wqXtFNpT_-P>|}`a=-@_EOMkXFW$@}%(b^N~XWhsszSCu;Q7t}jx{~I& zRVrpI(?REdCIkt+4J#6fyM)bg=h_yC^jth$uZemExV8w1;R6@WqyyU26R8?@s6u>b zd3C*prB|qv4@?Nn&(apCZjTpkGI{zk2wTW|CHzITiXJ^+ntW6CVc~X;cX?q>?1Gs^ zbs#pbWPJ^L-a`s*^!6vj9;_l?bKaaJnjmBF-#DzZx@%+BApdZlrOIqrqD-NsoV3|J zSEDL8CmcGK;0{9Cwfs>I`SB363bASpj4oVkth_-1mI493Gj|GG7ZS7Vp&K6Ism(AS z<=AliV~6Ybg``4z!3BdhOgqBfz-1&&`hA$r0g~Chs63{VhdpA~=`x^5%Qhwu)3-O_ z&>hi=4NQUjK4w+WY`*qMKGj%`KCKq%I2cVh^SND~naol6i&!Hq3~-+*$X34Un&HXX zkG))0nVTx8Xh`Rq7_}F6$6o$ugxsSr4mY<0SZr+!euH+$0xeQJ$Il!4Q`L-b0l;C| zXDwo=^z$^ywZ3+=NquoD>QEmjr%F_o2sAs?3zP#(q*=8`Xzc&)%eBg3X?(!6s|YI& z3EOR=p+|K~?o~3*DyoT?5Ef}Z8@4+wC*v{_t!8%a8c8$2-9Su$>n;@>E@MA()>;P{H(SV-TL4O^KQ%4d*+XUDKTX7tH>a{x)G)B=~^LR(+f!H zs6JLWxDO;=t4Mr{cDFSbRU)s`Pdx~K7obGahPK3TDhNB|i49#8$ow^Z z&04+Ux&>Ett7;|x@wb;=8Sljalcw+*3v8f6+z=TjOCd+hb~te))rVdxzK}=E(N^XB z#DDi=9ebc^oWA6RZgfi#!T}|-mWhYstI6?)wWGTDTdmSg%hMq48`h<`xx}iCOJx!P zR#`L}a!uN=LFM5L61bo^27q(wrH0fKV(PAj;-~5@8lDJUgp^0TIkdDA7}{@q4*2Th zaU`JO$leuhr2aJu^UB90;MUVij8tgAmox#YIlRMc796>HqG}~MQWkE${anjX3PvAB z@(sBC*4?Y5j4;Vv){82cc9c5vmWTxu%vBluzRSx#T8yqaDT|JtM?T(}={VhA+@`v! z5geK@!$jCO&C{2DdR*rYugA@)xhuf_Ob7BGPBu`tYOkK%>?d0iH2}*~#0w2@`nGa8 zFsU`q9(|z0)VZ=EWK^=x-m9!TD5f(+D>K3 z8pbGc7SefE{PNyX@(l>F|H$z5diwbB`OcJ-hX2B4!2KWUnET35jQ!qPAg~`@)jFfB z726tN8LR&bP1YK+h|YB{#oG~9t&XX)XS7h~Mvy=h;cb_S^)Yqs?N;P>^!@i(@_T_h z-W$9C63&I|;=300WY*sxuBZA2XkOlZ!B3u-;^wPo zm(fL;{kJp7*XzNVb=)Lk09dYalkd^*g7`2U^3Bt9<$@1X>^$H|cQa9F;IeCO^}zLa zMw1zibsH~>tQ(tRgVh{ihtC|bcQC#2CF|&L{E+~7YmLz%>Ng+;zg1Tc{j!c)=zb03 z!%w8jNHP;6?+F9d=`n{cg;t4)mW*Vwv@to{}H!2Gk1NuCBqt-Ya7+fUmw!p8D)cmvYGsA z_-|9B2AGw3J4I=~Z`5*Q-nE5ZWAGv5QKXBi)Aq2Wjmre~71W4K26(4PCcqVcS7)sC zl}dA}CIesraOL~Qh>0i>paftC=b~ON+*nrWM>xgLYi+j$FZ~?y4qAsY*D%Y0h6r+J z{%5@jYIJo(npWJeZkBMGK4#$J+L;t>L2AAmgR%F8YI&=wf?CZ$m%+4%19x_efF>C` zRYq^x8lUoE(^bK`VA+3OWyAp%zh34l5q{xknX5Tm1wfJOHm_cr^E$5gYEbTBd}Cgg zjR}9LKNsfkH|eN)a6Dh@V%;C4_5tlZtBRuV7UkwjM^Wlb&gOOY&`XN7G55RN%_#|9+O= z+^oIteD>5Om3{FSkU>vrdd*c?yx$ZCIBFgnl&K0bL`v2bD|y`+YOVaT@^rJH?RnpU z8YJf zVr1;O8nQ|EN*p6M&P?XTRYoDre8T>a14=GBpg5NEBJ0S@^${5{=6-3*vUQkv@%Ci1 zr$^{zAJN5GU44QFJFCd$0#6qA_-#*<=dIh6h(Yf&8b`L2Upp3F#YQ(Ap=-AdzUEL{ zkHX^7H1^M&3^>tVF^c{7ZWsnZK zjTCG|?hy2wcb2~NMz_9W#-@A2#6V?L;8kS+@MGMNdrA1Bn;52;2yS~-e}5iZbue(6 zYQDO_QdX(2@`dR787JYVn`1yEECvCh=_3W&YzLQ4}5`9A?)$Kp}< z`pDao01bqijia{#s@ThW@<&x1=l%7l-ZY33K<33WAgR5V!;wM>zlpu|EnTKKOH{gn z#}UuvLi@WHrbwn_o_iVGO*C^8aT7&aJZOqgGVJKpV)JiP6W{`jOZlv_iaq6%Og3%( z6a3f!9w!#JnFvWF(GL?AG6C|f*-E!V`VGmY>lA0sANf6^udOEqk^$cUxF<*qOJe_A ze6dgZ)2kZQEx^L_U7-k#s?CKpSF`$t%d0b|=d$OfQ*!&UAvNS!bA<{(h-EFmz|AszEB@HV<1=07 zg@dZ&%+<0;vESX;-u)f2vC_i?&GI0G3oQp8D`yqhH6&Q413nnq9z?nlAH-{@Ta*4a z;}4ioCR|sH-^e|S-mYMLUN5BR!S;)F#wHc7eGnYgy9s zFI#$p)>WZbP6s9~31Xj}n_?RmxTS?6Gf7^xwM z&p?E6ef~!*kpnCYKibHCk6eNN3o|^RN57<4_;(p`uCHj8k+{ClV_SGjSN#OqvAF z4>nY-kF3p4eyWgTXF3@fUp{9ZEua?&#Fgj;tKzwJ*fOjX7BpcK$6Tx1g#FCgDk4(9 z#P?mpH8G`{gs!T!V0xv+?awBKxSNO?MTF->#MEa${*MTGog=S(JGsxtm`fac5l2vuY7%f8&ykXv?H#Pt5FS5SzzSFRJfDn9V zLkvG>6!K~=!jZy4`V5~rM2vCUOfpaUml7_jrxsyd1?R;?@YPu-qsAS%?Ake@W!l8} zV4HEzy*zdj_~%=>aUQaZNaXECgMhOQi^M#tJdtDV>!=cvIq3&lRsK-Dq9Y)|0ar|g+7x*%bkq&=gYluXY|#TcrwbL zU<8P6@*`yA?&?>jXtly|D+Q>n6YmewHKi0YU+=@k87D!{$-kZ!Cm(Iu$Z3}+c7dC&+iAcc5;3EA4R0! zi2gR&&i5392_3-+`w1m)zT5fKw<&jHoW{;l2POT^k z8pj2;rOW-c+NAWGy7AG&S1lhCZGDt-{C!rqZ|lr4u4hs#Sdw+*NdNFA2PhBVaBZ>r z?o~tC?U}aC)(SWnKely+X0I@9cItL)Ox>2Q%~(=3T4j2NcptV}#WxomL51yE1xWha z9S|#80#i+4=~En}q30U1$gI01r$X|zfkfxLFc(+7UeZ@q$CrOn%-U_xa~BlL%eT~tFL{(oY{uQj3uQ6FbhV`6bqTjY>jL5x^+c?rDt^WPEt@G zs5ByIPY!5m^gL~7N$iBtA_r-{CAGod(iWvUsSI;d0T8>NXEi(X0D;X5!D|o z4eC>g!i8O?r%RM3aP^8CT@Tr!FMgYeAZZO02S-THAHul6nBCtMM}gMiSr7j&hv770 z0NbAM9m8o4R$;ybR#rrn(aLAL*w%0MG*8ZHQ3B%$G~+^t`7T0NMDAt>gyuHei!uIQI*HnE=Qijm^yC~VM;Yp!(C{o)FO4PbI#=u3!^^63asK4Q8l zr#1t~t{8M#CUeGIm)qD5%qX5uUL-3Vn?i>TmUt4pQ;|7;=Vq_hR<4B`N0F;%SCuKH zE3D9lsr%4_VAb*0yfI?fi~}{kw{fmDqfI|hJj!KEC%}v5J7}Gd7*mZv^*n@*j_J4j zdrC>bPt~&VKeDDd@MOa@=8V~{oLDB3s^xq6y8`av-L~4y`sW~wRdGMy-CEs3Tmy=C zx=WyWFM8;VzNZpWK}kT9%WzbkNc?&%7U0^fo)Jd5c|dMK#zG|n^82wNTp;j!`mq(H zZ#2iO-LzVDvp}Pbvqe+;J8HZ+oIn!$<#^!ga$fJa+2Qt#cWy;$qJBU^+2Mr|8ohp2 z?>?SNCFye1{h=#MOP+*=NK ztdz$IA+a{LGHU^)X9OBNS1bebag?|$163T`T3#$-F4#SF)BclADGv|a`8LYI$@_SB zuuAno!Ea2x6qG^OInG(TNYxleKj8us z44pXBNM`&-=1P`2)wQbJBPC2e%T$qKLJW%_Np`c}qA7gDrfKX0RiF0Nh2%5B8=6Rc z1r3?}3L^5JTOyy0LTp?I%$B)();n#4=XgmK;|8kyHr|AclXe>Ymx(aL$Nifv*Ag)N zyxv`L7p9CS%?}7dY4@3@P8ixPy1kp>=bY0MuB>M^acD_>#F65=^1aBF_M^JXAwmgy z@wn`%BXngUmq5k zjxA4GiaWX@b%cr$2Ne+A;_99;l2QyuPrf|K* zR@S0+-Lg~p3OzeQPY&KCN|R0gqeu=KVJ6?k8pod(2TMrjm?qY5U`u~TSCHOR%a}Um z;3UlRG9kaC{Mk-mt+oKeIvGi!cK;OZ;`ZF8FZH#`XfoHh!hWbxkJ zV@H)7(kjm9dK;VysEYg~Gd5qbp=iK(hMGh1zdqj| zr*3m>)T)wr=8mzB8?FRjculI&VPCK}U0S|&r8LnO)w*^fuEyTG7X`|Avz{EQ{W|>= zY8XJX_Tc0*nd+4u_8;>eRW+`E5da1#z3t1s*UTkkkqO@O>aHGTY)@*@A7#3n<5J*q z7SY<}5XAR!rk@j1z}|}zn->V>Ck0bYSv6plk-XX@30+k0a57_M__>=^?8wls1_A~t$R~QD=?J3 z%vx8p0pYjz#rPuU)Q&f?9n(&s23^T?IttS1z7~t!^*}tW%rQk?U3%Pt7Du>g#L3|A zZ2I7ZN8ziFTptvXq%~$$81RLHSY^I~_TT!8e2f^4pt}iD@4`qg9eL}XE!10ZHV)t% zFCqETZap55QF%2hDx@6^dm7o4FWhvCPkndk`YHJzmhCBNOgYuGfAZRHzty)?wYQK~ zVhV(_X-tFyjqLSi!rTqI)E9m=Z(`8i^}{meuz6HqSHX2W3uY1|SN(rB|FV~kGHI%` zfL=KdU;UB^j9#d5PS|1EX$`+xp@2K{J-B_KYsb1ZvP31;{`d0p zSD6x#-jn$K4|DI5W-L13tItafM@YfjVKKgT`O87Qc9HABd-0D&Acx6Y5kN;+2wu22 zorp>B&mxX-;_sYhNluy^F0UIkgJJm~-%h~I?|oqHFNF5(6zpF&EHqXkl6+OCkCaLY zEV6G6vs-g7@5f4`R=^7BQ=uDD>q#MF!;CUx^lann|C1k$b%iA(4_18#`dW^C8e)Lp zgRO&*S!yYhe_{RoPi8jyBBb|9r?U5Llw;j5MvrCh3pd~pB(weE`E04Hq8GF@^z8r3 z0(i#&p6bi*N!mn$zk#3i)cV5dxREiWh7?8lsJi(wA}3HbZ2l~$;NST`Z)^Kaiix!} zGxW|~24wWJJ44N8xV#dt=PlI{W$)?rI;NCCHKW*{kJ)px$JCB76@iY7+*f7K(CdGI(|vk9bu0 zq!e*^S2q2IX*NxcX&a%F;(712ab4(`Qc~*uQlHK}^xhu_f=Tzb3-7|F&xg$oZHrAP zL)6`9;b?W`#8|ZF+l9ZWlps9R83ZK+@2zk*ytRDmm^uoMQ-APH-UbQa%`L?HTdGw& z_W~_W4s@es_L_O^e?{in`>+?AO-u81TCWf5_IVgi3a0}rz{i(IMlAw4pSt*U`&{?8 z^!5+~T@&D_D<8W#|IuQ;>>97+v8(!sjp(bHqX_q6tW!dGiOk9@1nohzqfX)+>V4ULzLq@r(pPx~M%gA_7RJk}ye;IPz@|6vnU6ug zz7ffL-}N_fN}z1U6dgh7__)Z0t?}u+8`aB=mDG5t`ZtV}o0|D7Xk*4KC|@&wV))1t zz%kK_Rd;$Za5~6@2LU9S$(IdR~N1qq%)N`O=X>9w{ zvyK}8t0(K6GAw@xdVJZQN_O;hnvJ#aAzz`qSb9$=#;Gp+uy|QFt}>j_+xlUTA1isd zdR%V)Z7a0#nMgTlhxiw?4AQ%mtbJl@RGMhPqNPB%f5$L9wh>>&zpuy6UihM*ffa@S zxrj_}A}tA7@gR*FLr4DnC(-f;db$_{4?SFJ#_66l)kf(k!Z>Dd?R`J$f7GXtrNb{b zeECOnZy&khg$~@UR3>m%gqXvESe0a=&f_7E8-L74cn%%>rQ_t%?JPWwIQUse%ziCv z5pT&!90T#(7otw?V06yc6(lg@POBI@$7^?J=l6g|nF+bQleE0LuR=G% z(QY@fUHUpMZ?s1BvTW$!t1FqP&i`4_FxI#~L)0?2&W;b^K(543Paj(+5XJukdhpDM zaB5v)8pJ0k^XMIf_M!Ar!GdoQqkzrXl+Tk4%3E_dX=A23{q-Mmct_P6;!Yw}^G2)e zlG5vRipJ z3&>+)qsy{MJ=B>^vAH+OwSlvWCU-epksz8xCaog1fGa04w z=sE)`fW0$GshQp2C5T+@e35pifrHzL#rF1`EoJeLWx0iB# z?q}J^(m8j%$=K@CA;IS66z&!N64><#V-RzO54tcKt)fj+;ck#=ud4T@+$Q%_<}%|} zDGj_#)H7oH#mM#c10q8B3@D)w9)OBmaRF}bNVy%USRL(Dh`-;Cta;0Q496r23m>)m zLuI9)Kt6fD5S@VZ=4AtrSD+9=D%(TV`k;2DinvwMf_1GVOvQxpd^3C`_{v8~V0EkM z1&?%*%R{}>7q#OzZ753YQB2he1^CtRYA`($$>>y(goJQjqEe^&2H@ilWElZGm?N4O zzW-}+^u+}AjJRE&=T;-Z2n)gbWm&{ZWZ3?UzNLHxKjtb(0iMlL&GS6KO-Lu_)h)|> z4ogEyFG?>aWRKUblC+1AUiW{7Ysp3fnbK^>e|(Ms@}0Bcw>r)*)c$uT9qz#OBrRCF z&WWsVL*_GWo^my34J(3j>EM8?P;H|PWayRlfENp-1B-S2C8| z&@Im3p&%|ZEaT~q@5S^(Xr1^)01%Kwh_Hb;tIY*<+2cFc%oi%CbCe<+lfpblK?vQO zwHj@GROM#D(S!)7s2G8@!?#94W1$`xM1nI{V`D;$*Ia-!rwmko+HNZSOI~JjHk5iU);x-_P{LE&Q5#6Za#p4-T1ALe9}EI69||4%?5p?Uj- zxbqS?qw*>jsl#^p!yo+g0-itx2|!D8qPKN%>6~}Je0HO-f(}O02pj7n>T*CD8$4@^ z+|eSyXW~xnlvP_l4Si)m_{|GRX(;9--}w25byUUz05hM?nQpWIjNVw-1qb6CVsCQy zYI#ewWj4apS!9m?Fl^1vVm&PQ^kIuo;l5+?&As?ePNZj4L9RsX;EPre6-xMM;M#;y z(EZp+A-L~$5jIf4io-Dery_*Ml|;^>m9Lh0P!;oix5qto5r--MLyD9ne)upiZ^AKz zutbYUWM?kr=0HUcZHUDH09ucJQD#RstJso!{Qh*+#z)hoU57B!Zfrv&`E!mO{NkUz zli!16Ty0go2b&o(f(k%U0FkNy0C84H9(D3?!fo8T_l+cY1b51)F| z1^sIdV1xe-;Kv#UIG0m;1r*LxXf|`lfLw6<^t@y85jFcLr$)ZIIHkseIohf!&UK~V ze<_waaQS~{JqrykO4L6u)kd$*gFjiLfVrfUEIF4G8D8adV{Pnw>|L6BrJt*dv!R52 zhpMi?oc+EpLXl4OZQ|+@WZyj_r^~%U`f7y7u-d3|rjKFY!Melsu~$fykuxrbpg+UX z(rh)472P(+cj6uHaUv7UQEUFZ%Lmf^y6vgtOXbY_?!~VA7ITpOSk)^-O5)Xr|6p5A zzXk9`9`5!S8}Rc|{`E{TBwLvVE$tNGvWmWU8F*)cQ^V)0?bu8USMt~vnXC3z+^~9x z`gCwcmQKEp-m$j!2n;2%*bHzoDP&O{8DY!rUIndc0)d(<^q0%Z?;0veJ(x`ZIx8}+ z# zQi{0rFZ8Mn!MDGW-ole48o}qP+5aCl-ZH8U?%VoJf);Oq;?nX^+}*>|0xj;1Dc8g5B{ypdhN=>(ZC8(8E^fL_ zFc|X&X($Y|0{#^#Hmb2aKKyYIN383WD1zc}ca~Wu z3+JZ1qWYQk{aTuu0Q1rh9NJJ9{gOydJTG57cUNy`J_12)OuK8%Lc!mQ0BZO*1O|>1 zYcRLA$_QUFJKI~UrAWF66eSQu+Ul*!2A*C0ad70SZ;^O~y!nrz%dvrs=b0n#hRTwT zg6qnv7JfPa@)_<+u_TQ|xYjmHI>{h13PEZyGx&4IpJaSNfcJnxhng?@j%2X_&wL$i&}m77qUdAkmrh0G5(XrXO?D}Eh^N73TF}Y-~G?rCFLvGAM)OR z*~xJ6-T=LG*A_MylISTSdLb`siP5}(Bx4cF?5}ogr04=Z)mO<2{ zmJ7vrCdP+Si%)8c9%=Lb;AMRJE!Iy6r|9FT+eQPTFS&?pD?{w!87gV+#6FgliC9RH zkQ@OxXUy|!N(InXO)ekN)Zkp&f#0o+7s#iAWFAX1}_mCs%IM;n>2p z3DT&2yEi5ylr30)&bPAaf3tSM@f9IOLIbh>e)rxMML{RU0`MZM zf9JF@y|GO1@9UEEYmKEvv|7o0ljT_>;&Bigl{Wz?)D4~ory7*Tm3mCJbWoC;)!NFQ zlrbJ$mZ(8-22oAtbo4t|L}^lvS-V{nmxY+aK5<+{bq1cWNLt;3eRjUb@q9r;6IXwF z4S~CCVAC+}x$rCV)Ohv~6)4B_(-vGG^1%JcQARRe%QlaAlXXuHchU9vndshlsU;^i zR^~6O#o-&SWJxZ32%&gVo~O51bUnUrIJ3z@^UgHBCfJf^Ngz3r=&P5RS6EWAJLH|I zW13n{=fp5?QX1Ptja9eb)q*44sod>R1M=-Um({C53r>C5xcsg8XB#^3f7;^zdo58# z{RGSsl-E;QqZXewis79$C&r~w!6nx2?nQmJ2mR)4;ynD#S3;KD_t#_MN`7d{!WP*d z2XD^WKR1deOlqR4X14YnbDJ2f`M4lDZ6NcO#;LL@duM1AsSG5wiW+5i>1o>)zuukz!m>MdeNZT zN?rwRixzgg)2l?NPT`p6PsS2UC17V@m7SRx%kZJStQ#t%scWDREQ9&=t&HdSXtaJ) zXDTP3#Snw45Lm;$*Q^IbPy|*&EMx(-AVhO|Y{3Z#eDi=iT73JhD!p=&VRvl&pwmj}bATYBj<*+FC zcpg1`oGCQZDav|TQ4EqHuGzoJfF}*?v~gZ;&N-T>n=n|~ zBVY3RW>aM`E{;pso{8hhz=cmU6cFfO%2gEH6!n69&u!LxNwOdS2Yo$*=KL7e1h-Bk z&KNhZ8wI$OaHWrWgysNs61}%+Df=UdiaL2F!{wW3I*&PKJPT6>(2%+ks^8(am!mE& zJr|w8Ud8TZeB8Me{zYGq%F*aY0B6n&s=}y-3Sh+!y+PuyxZmx%nt2?km(#JOsYq9t zwJ{IWExgE=^}sI>EEc;Xf!L3{d9Xd8JhX{-ogNlKg;P3LOIgQ)_h& zwx~|?*(-omL!nW}^*16~&dxW0RQaaSmu-C0E9*f4e5I_ldPkAVZ z;`0+*gkpwepOurC`MgdTB(JW5Qm@jlTkM(tZ}-)njjAVeTa(u2f|y|e^LIEln68Mq ziyf8>wXlGsn^w?`HJ9Uxa>c`|KUa5T%Uj+XA8GVi`iBUJ=kH5uA}!i%yBqq>qmo7o z-ftIm9Zjkoy^eH6xBUk-B~kt8@G_E*XdR3B`s^~ZBu{+4t?0@t{Cq}Sfn|arU=+QJ zEZ3xKNJnJ3d+qb`D;rTC;UVLC_(uy;^?!u$2`!y*uMYtN$A{d!!@L+YY zc6Xh&qcFU+r6pMqeVL-g5P?B-Of}7!>!Hb$>6Ij&&y@aZp~@TjVWs!b8KFT1XGD30 znf^GNHw_IijC51GTRXYqKHNX4%T0T5FBe{cZuT(Z4d;fPzm56Fqwl~)Dnhv`R#!;B zYdeXQ&=EY9k|OQ-Uu238xneT5aa5;HbN$w%dZ+a7PcIL}I!vS#z^947(#qnmoOzpY@E@Af0u&M zn@##1IDA_s_js?b14z$l3|-OO4AcdV{CtN|VGe$Sy-;`zt7r?;!PXzLa4v-HK2sf| zUPM2>;QDN~_!q=`*Am&mC3oGiI~lrqu{ufxw+Xx}F$#0|I;Y|+>$MJlPW^`u3Fyzo zR(G7JTVc-A%_?c6q80ql*oVVq!qT+?I75%vn#Y>1!pFN^g*Dr;%_%Jfw)^!s1@$C_ zhoJVmdNs2ZleNxnZE35=QBR`F$F1k7vwU3bX1ai>aW_Uu%(mX-EY^K2TdIr`(&Aa7 zw?JpOX%O%U<}34tfRz5HAMU_#T5Fyn&ol(i>t>=;3*-a*DGdU?!oWWlH?$`-&!fn}RhXMDqOW98R zLG^;55V1Tc`BrkgirYgNyZx)ymg$(GlvKkvj56fc+6 z&ntqK{$m_R*eNu8P>~CF@rPl_F!i_;wR*he`_C#7p zXhaQ9OoluO!W+v5*)gpt#>cCRADe^F;Gt^RFh`Yi$ULXyPvs%Ex*Lf^Ply=Z>Qnsg87i&r}O zxlc1}^+G!ln=y(Dw)Vjr&y<;}EF3}~4F~q8^8{l+@w;kfkw&v){!QyHke6ET!P8{+Gp0*_A+ zbDbq5xken0nMLD4Zd z(&KKvR&s>SVfQh>%6d5WB`Addkd0W4c@F68ER&S&0#C{KI*AwPttg z*4XILXS0UX)zupU#$AVZ%cU+4_sOqgOE!A%51qLRY99L~Oh0tjofK@d(_H-dOgSY{ z^QcVe#C&$JPz?7INK2e@}4dsUHOwU}jTd?gkr zi#A4Bf))i(IG@zz5ZBa}-xX{r<*_g1N6Yp<1bz^Tf0-H#7y3ip`pLh+opYjT;dK4S z=j=8n(u|I0zRg@nXT4l%e~MNNycy&YBWvlgA8JUw6r?MsQ*rft9{1sI+_xfWO)>V6 z*aq1F;{&#jycF|&#ns|PvPN0MI$&=bN=3Li;#&?A!Oh7r`l&@|(0%WYlx2xJ?~z7X zl?ENV

    B*rDb54_j>nnaNa+iVkRSji zIL?ahgq21)j%2ua5FRf%U&I;Y!2*=J9~q$~pYrIjn;Ps{cDMq-RL4vy#SUgO$@*6|KzLhDQ%JcASl*A(R?@GhAuQv_v; z)iZ6|!gMeXS1sLDKJn?-8lmI2#a%Xc>1XEszI3}t-^l;Q!u=Peg~pV??_#G)m<#c1 z8Ttw-Qw2!GP<_#qKeB5Y8HE`O;J!JBAe{$=$Z1p071Pt3J>Wqkv?(h*qUR$?aeXtwsC+5YACHS9@E5b

    y5W%`<#GLphl^L3a#L{44LYx$79IN$%DECAd2XAb6?eAzP+=&@wYHh}-|X0745;+03gPMv>4>BU78tfgmJ=ifVjI4 zAuCi$<@q=&a(&^=LVV_pV8bkdtW9BNGMT%Y7Zifl+JHoE7EZ{(`Mosl#?$;iW8>w` z2k4Q0+lQHHc!Uq>r2d~$5C;a}S{TCtR0GrxAMuLqnR1cKaI<(e_8xA`R!(=@-G)zE zJtm2u1B0{;L7_N0Yl^V+!a`AY|!dzh+8ELY{A`ef?&@EPxzzl8HF4=2ytzh+@7xi zJbdO14YzXHGPbnQ!uX{$@N{o?%;y<0s)^zcbAi0szy#CqZP!SH?e< z=+tb>iZInddVvwSVy>~%tHc#T8+I!Lq>tRhml?R?X-ta*=1oH5CYfSbiAXVJnXQt* zya>ZQcD3izQF>6ts}3CZxW)Om*WV|h*~4U}cFeJpD-!;apU{|v_smERoXEvRTmSTW z1+zNJ*R#w}72V4VS$N*)H)E=S`O+3J8JvzPLnwO1e>}Hq!4BAkTzeBt8V`*w`;1#O? z#e9^HyYEM<3fSG=SFC@9q2;{O0N#jEPiSZKz^WB~6?*0TVGOz@z8##i_M@A{Z$fdu zm*t@rc`k>Z)~i}GQDY805<(zDQC-)?&Z={|t2M{}O7vbudz}S@EA46y<~fVd zL&(snA=(#;23;xGFGfyTY!gY%!h%rf9(o-!wAP#dWF=u|;ycwQ=o%P6b zSqM66Nm8}ZAlq%}jxY~cu-{*QO;(1L+a#`pZE5Py$_13($rW`EW6fuG&#z0+-3pO| zn7?&)>3&Cb14BgZEj?V;pL(>b^sjQlGNL~w=giHi&A8TK`=r)s1>NRa6Ycw&#~9GRMU>D_;nhk<4wd#Rx!HaE$4) z&zS}p-y-NTcel`DqOiGieH`91pyavxER|ouL4^YO9+zM)b!GKSYT4wM6o`3J>U#q@SRBWmF3q>_aQtlUYj^0 zU`FY^K5codBFSm;W{uX>ippSmZhIKcvBx8(%6amuFW#B7k@-SY#l6@FxT2WR4~}}? z!1&rK(>6Qru(An<6=xiz{ZuMf!oPUYF1Tcfg;-VuS%KrR={&)gM8o7Jj=(oUH&m#s z4N{C12pLW{{_rhDJS(FakPE9}^&)RUkHNp!sWNhLr0jEsxZiP}0IYU^YtD9@i*y8F z7v5N-cl!ycXN#3S4vbUE{k-MD`o9tuC7%wfE)p>+TM*Yab}srKH<>pze}li^aLz+ZBq=VGgk%$El<5l`vHf|xnv`|RxA?961ge8*vE64!=eoa<(;bLB$lC0||5>q8e!w%R-T zi4WZ1ZY>@wmC=8~k;C@RMcACWar`f|bFdSA#R{yfc+IpSao$v8y0C4`n<<0ArKk5Z zo$;@{3muw^P4Kr#zE!MN?zk%tt>Q^?PD{_+oWa;oae>I|3c%`= z=50O%6@2CYX|?4dLng4AD-6|vlE0O$bx7cyJN6u?KD!RlI!=1FCJYNeqJPGZ3(F&J zc(3OWYili$k&PpH!jZ#w3w0PhAHXiToqgQz>bBPfmumaz^)Z$EWWrRxS-!QepZ1dT z5JlHVps2rOod;T9-^c(y?D13hoWCofv)=BPgplE}gP$6Mz5`FC^w|SB6gse@J!zEz zctLfwN~v>7a6)?~uP8=1SS(`T6^-!`Mh|aFUwi;yf0g<(>AdY~d(KkR7q5+5%J$Vi zcNX4eMn1@&DgG6kfbMT7txl9FYqZd{f-Dk;|%6nj$`YxxG@!n-?DneOtAM-JonSiV^#Bnq$jXC^% zWm(m+wDjy^KEduYoJ7xxR+9%4y{&2qSD$gVW3Md5XlzPn{huUh-3R=ck9NJV#R9Rd z$(Y(a{RJU@3ngA~Rl3)w0&?3zTwkKSqhMo;`vdW%+*@h=i_T^@lNj)f8^Z4B^@<88 zymnmvw(ZN*<{r_ZMpi{Be4pM@!pw(Zyc$<&fAFr#=Py0Mbj579ZUT?;Jpqa4#m<;8 zAwv?N`Vw04POiD@_Ob;=`t{@>=n%Q+S>S@q%wXUw)DZeQQ(vt{S6aJD{Ga)&CP zmen6Dr9{KOIft$!Rlb9VuDX0Rt)n+?RwxA#hZP4ox5L7btel3Lnx~DBo*8VvGhK&vj(?#EuLN0VbMp}N0C1vX_;tih|>D_f}f=4s#gTATf&hH+i~H60&w zX$wqFY9ja|wNV5Zo)`ImIe*|ysyLUb=8S5#w@mfc?SDtd5jwUuB%Fr`xgxX8gr`X_-`pXGK-tZ7(S3Y?XlTrDJIXJL!t^MoU_YRKnZts)kR zX81;DXOo^#TD_gJX9@hP#4_FjMqroyIE*p3`m^cvuudpS0eiU*mA~m}nDpr(qx#{B z+ulAn7S!bC3d|^dtznVb!$1*l7xfPEaZLA-4j1S|ctmr?K4owc+HfTUN~D8@X0xm8iZMp65o^O-85){7wL*!l+t3 z!PSU?mYCXWcg$ka>VC$mh`H<9D11pqRDUghulRi1vnjj$0MQJ}x@0-VO*u2)9!|J2 z@t9o>$ajaZv%Wymv&}y4ImYY+$VJ(>gIEnOeYYvai{2aFDSKGErRx9+2_0lVhPRbj z01?5y(T{hrx;G)klco)u;0;Ta$}Ni0p`a!dz~I|5gWe`u0BG%c)&{0!kD}ckMtGh@knP?hX5Go*i z^y`^JLG|uXFNtKfM5Lx^0mgCIuD=*I@_QxavVNkO6=yYk3kO-4Wl<#Cg(lZ)b8+)~ zl~*@x)}hHj;Pwb)czLi&>dHvY6jCexM7;%L@mR|G%i^yDE(wJoes%S;pq19o=A#%A zNpHM&;V>Kj6;185tEW6z$gU*K9>Vw{8-`Z(@w7^aKigH)4_|7;MP8y{mG*Jhg+0U?y1mz4*|=$Gk z@$l~2IYy$phcoXHai8S#SQ1imMEu@_1%Wl59r$fEe2?&XtUvu0xOJhU13)Rtd`FOd zweXBnTEOTB$h#vt|IA_t6z*)YByIlvk&PG~7$230R0zMcV`(slZ}rP{s&H{PvuoPR zr(*Q`hfYod`MCtJHv9Q8WMYzdy#M0S!_ycuOSz-09df>A8PyU(whg<pSj=w>D~acwf5w^BEn;SvOGw9?K&@DH@iA$FE6;`lSO z+=)!@`;M-fs*TC;@-5WuALf!+Qk8RqDr+@iJ%&0KEon&XR|fh?g)o#iP$=qOR_A%{ zj=Q=LNmmcHKHK!^+V_^RJMNR~imx@CN5l-DTy}B2{crjl8*>d_GI z1PW90B>#x`x9X7Q44e7vnbUj2)!QA$F)4Zf@;6}CaIqqIB4Uf*guV<%bd zlF16Ns@P@DH{N?ueMCp45KxpC+*P%{KAehhx5K@NrmeE#XstL0Ch_3$>YzbFz`2nZ zYd5T|8M~zZq{(XLIwJ$LB&QlV?ZXZsU1PqfVPnKO)W?lajbYXsVTiUR{w2?)pbtw~ z=!T?FmX_O$a3Kb9(@-xrtp$ldgRyOl?|Z3S_oBntH1`u)*`SQFi^E+O`*zUW0D(Ok zr2s$bizA^+E7r*SPT!c>n{tYuE~g^4Robu&G9;3|I{MqY*&kv9HxJiG1~(H=Q|$_^ zayfS2FP3R_K%1`W?bY}!Z8SVCMrKKk&{yAt7y5Z17Vu25Xt6lE;!gR6h+>x4-#oyU zk9&yLGlt|<1K7!X3d7|S{$y%wc6ucFAqIeq&>S^vHKjQUVa}Uxe0Fvz{&A+UCOB0r zd^Jd~hNSrKMwoW@$)5zCe#y2rqZ$*oCRF|Cc{QpUwS>JohK?ybh9QulJDHAI-=WRw z6Ssaom_#O-S8~_ODDD~b$>NwU>KxYIS+mNtYLxD6+V4zPf(XrS^q@XvBtH_NkgALlx%PU6sQ3Y|#s{iSxoPWPFY(F2anEFU# zkwGSRS^Hm9Oaz`q=pW6+`iB&BNu`4QeQ@aE_*ldvLG2BkK(n5)BzH<5Kt^2yzyTBG zQ$O$6#+o~~IV{nF-*6Fp5QB3-O;~eY^tuVTz%|;8f|*YL&GVcPviK#BC)zGdqqJh? zFr}J1o2k30k$d-jI?L7IS#2M+XX@}=K1I1q*`}~)l@S~M+s~3>_bW5s3fhZKQkSPV zQ!9|B@^g8l$$I27t*{>JqhbSPN8l&13PZZRmnFqK(f6i*penalw?zuwH?5bsy<~L( zLCcI%3y*+B>8rpW#l?Ad2TD;4Mx!82IRT$_lNQrri|na3z1v3hwDCXB0SbQeJ<H_?T;)eTeaOENzXzPsw#G_eP6MYTW%$#SIM9&GtnZLLF$Ks{U^*r47sisv#UE76419?m;oIW zgq-{uB^UwD((Wj4Ux*pFuFfa>!~D_koz9$81S6{@gLrif)q;)UiC0?F5FgBh&DMf# zO(48Z_2PSdhMau0&e3glJSm%4>A{b>hgWHGdhS7|qa1b4|5#Qe1wtYiw1Vy8USli2 zT+`+C)Lq*EHUKTai7H6vi{71=y{r1&)h``6z{cToOL`&>5Lks#jsCJ&E-!ggOX1ag z_-dXoDpBU-9t0~?-}Xyy`dRn0?s_)Yfx!0#xUfyF znzsX8kFC=!R^128Pqc6T12me8++t9|Ks~>woi%T5RaGw8uS9U{K4rxvj5jFflE5R> zmd=vafsk1{mH)dEL_mn+&md0ZH)ybpJpH%)kO#hjUmW)*co zdXDfTdPP>Mq;KT3rIEb}62BIFjff+f1NYJja(SYP>YJ|cfB6{H?kfA!j(@C0A)|ha zfor4AD*tJw#km-w(_j#p`FAFsTD0#2TKsssZ4iYhh=?DMvX+5l%nLiv_Reo-^);sa z;q(KB##j99#(Z=av^I}TXp*?#Q~ZhN{0+R%4K(jZ3Jt*4`q{|cd|&S~O(Y7Dwf_0C z$Tun{(5$F5Ln$T{PH|urvtO#iw^qxOc|GIsWE1(t0&>jY61Sw*VNg?9;-8b@3pWtg z(Jn^z&Y&GeG8|-+<*raeyhx$!7!x+VQUtuyN8QY?I*L3J4<51Tv2lEyaY@z+LQx?6W%9A5%Nm4^$KA z7K(APc@LLYN3ckhQ1n6OnDn6=SGWpS2}(*g;JUe3D@$|;BA~j)kr!6~S?=m&c{T7H z75*7R~u zr6y)y02WxEJ@Uny!40>Fx-uLqT5#g-QSQM%zw*hA;s?@LlSpX;h2ezf6YXMxryNW4 z#LJnw`r3p+`0Byvne>ro?Uvq7w90eHFu2WpT|0;$UTL=Lqb~Qsn?28Bmf3^y@N|+e z2X+x@6o*x`kz?AO8NRq!324EOv)CXK^cN%uV<+QOWRnooekQXR;J$Jd0?yOiKTwb| zNhU`7gE{z54xEf8VW|&m0(tMoHBHwK7D#-TzqhnmQa1fs-{|*ut^$aDBw=ifbg6iF zv3~fAuur+|2VB&Pbnjsx@~+J9z5*j#mv$nl;~!b6{7LzsZU41==G_mqc&`3(}7*1 z6D{XM0DVbo-}aFC-7p-Ok;BnOziWdBNMWhD$+wjXGa~47GudL#6 zC!Pa?McQs(4Qmm@_IPwS7tiiMk=AIlDcVecLfyk8!eQ!-k;&U1s6}xh3ToRl2{qh# zd~hiLTsZH;2p7Qy87&u782B6UYbRGBvO1yRlNmsjWuv?Uz>3k%QijDcpY2HA+HK^HZ= zaQ{x803+iy?bw9GO3@mig?@LgN_)#ui8D@c`a;IBHuM)My0hHW%WLh3j}vAd4k}&A=eZ~t zi4$fS4&y|X1f?$;iPsD;1^(o@AlU;NX@@vya|GG3>V1*b?*TstQx6YoUjSRR^Uge| zZa}!8jI#$S+C|0j0&X(u8XSJdx}3q$%(cFsS2!S?!Ys&~y0!K$@aa~#=k}`GlaSUK zU%5nYY71G=&MZKS^9)4cIAbxkWs;MAsM}3U1E)R%txIivXYw_4`QA;{VFfnoxPq58 z@9*_qYvsvapEi1j7j8n7gdKzL)q^X7YRtNYR)P>)&i%{Osl$8#FVbH#)}mkLnkt4a z$`~s{un?R$;#blmrd8R^5S^Cj6Q|*^$Lp!QUvrjLFN0=R*X#eK z#(09S_OX2%<)laKb9|%gK@g_8Co)H+=}~u;iLb1VD>L;b@5$rSNN*6%n0j`fdD;|y z*pcsk?Q1gMrc&l?O7QgYhg2<7??QS8Tobya#-0mO8Cqz8k5$Nq6jwvX!UbGs9TiWf z$2SQ!=zmP^xi!mOxsPME<~ALZQ0ibVjyI55_y_p@S3G|`M){-q(%|FBc#75<&O4p1 z8iNQow{fF);iPc9w~MbnlT@sbEg4i!L(jgb&U3_ct9ZLQ$Mu8>d5qWwKgi-NqRXcM z{eS$USnGCmSDOj!es+MRhWFB#Q&y}Ph-hC|q;||5tzOXXGPvhg&k~fTR@H=w#Asb+ zUx?F;VWV?8M+p)*01kyzv&A3AxzDsa>%D*H`84sQO}PDpH$yY(9VT`>EIP0bF`YWm zVxQ|MT{QtSgImO+)onyU7>~b4b;XN+V|S#24<#TsqNfjEb`NK|`0g36{sQ~L?-3Q& z9z0tGSzEH{76hep%E-T#h1vU!;av;iC>YAI-TyF4Iq^-y4~fnBdy zeTaLlZvU@Jr0dloGD4+oP46Tyb-bqIBE+cQldjwT?gWN1`Y*vBSrd+2+rKSQ0(QDz z^AGF%Z>3+N1A3H`GYWDtg&%q2dufk;TWd^Mr)_}(WsK!6)HuC{`kuu9u1{n90m--; z79buJ6)PUZ8wZYaQhMS4gL6|!NsDs;_#XA)8}V#kKxyJ!(Qe*jxGDR*J`UeQ!Bi$? zzVuSAgQW3*f5q$^j_DNIq4t^mbUIUwSj$|wk&FlPtf_|;!4EQKu3p~S8Ts|+Xnd0M znZN6-4QCc(DVufFFF%PfE z#Ka^9Zt;F}B|i)l8#rEW&3GM5h=x; zS6}isi4dtvmibhTgBi|K4r_jBqwchjClqb;({``#Yn$*N=qqQsHSlA)$Vm>$?j-z3 zgt8?!=qy~b`nOoaL5{)yRgGwLE62QZbl2=V`vO&m-MC* z(Yhv}eCNV4OMeY<*@+goPDAz>k*?3ZZQMv5*sxz_f>vfbVE73MFWxW?PbM3ni;Qys z@3e~Ki9*!x>~Vb1x)>&jt3mOYbxnw(L;U^nPsX=h(VZ(xXM0m6-8*f=D$gvh36a8D zfBTu`ZhsZ2J$E?GFhM)a4KdK2J3L_-<1CliyR#Jkp~HoPc1dk1cZ3GVT>$MqOE9Rl z2cimuR)&r`LiZeTPReWSgz}Q&HG0e96%h=HKj*5FSA?Zy2$B`(-e#vB+Hh!uZ%W1V zmHME~=Y`|&nv(2{hzFFDRC8QwXC*j3V4-bCcE(zU$#V#Y?AU|(S@tduWR^(u0b<@T z*p+^chb1(o>KmFOM5aABUGnl1TcThps#K?N@*PLc`>l++(|Nn3%&LpMzlBrNWqN_1 z+tXD4|4pEC>L~@lV|?JxsK@CavXs%lpKnq(9ZW8A=>JnH{;ZWo=e1i955hf){+}#B zjjEK@j!GtreK_Z#9p+a1LB8=<P=5CvTkyevtJV0tFUi zWuhqe<=|q$dwI3g;-1=)o{978xAa_p@n#mB||Pbiy$ zu(cK-A3OPP_&XVOF-|md0OAn0s}5NF;Lu$u9&oZO7p}XGu6Y=zsrsa%vi99UGveRm zfs2!Vtn21Gy^kk9ipNbdVCWwu_J0o{3m4?K;|~GN;+D=@*VWPQiFXz+dSjU~#C16C z%{l^_Qs;DPb8lE8{(RequHEg5hWBp{N7L47SrIH(^#~@}?dZw#-^f+Suqg=M(*-B- z{g!r!fxIeLN$I@|=jiF=slNGOf@eog_SRj%{xV-NhJ*xmcm7XIK^#e>R{KFkBviWP zT6W5#CBf8Gf%p=b!^e!x)Oa%eIjpl_M-*y5v(a;lde?v(wUA$H+vgJ#+Zb7^Uq!$q z+6mIuOO44IeS$+k^4!Y`+RjzOx0SgI(06Tm`cow-x7hHQGnsrs>1;{y3|C!6(^y=Y z_U)*7t~d^~*D`zSB{_e7&T5bD;<<8Rqfzj;Q0NsstfTu|agglMUoa*#wPvdvX zT|!@NBk&-=hb63a*i^GY@#*Nri}A0#*J!%JGo{4CG2LbHYUPjZ+(}AMMe&mJY2iwwZ3+nRVp3hsxUCzz2@71ZZ{TfFwDQGY4{qR)VDM$x0_MCHI|`1m zv+ySN#>UlWblBXlP;Fyno6x!!c+|J5qff=3yDk4p5YwnE3(On8-ezWz^7+LTRu{l5 z?v~LPaI)Oya2U20eq9vD5-~6CkaC@eymt(KYzypqbc5liJqX-eop_?;Bi9gjRqk*; zl-2NU`uTOm-TmU>cYL%I32V?y|!% zyhGo`OdDMEN3%|@tDCMPHB*teg!ptdYy1W|z7IC2rnrl|ixZUD)2L72H>@uyo_->H zgA1!7%r_6aH<+W(05cKYa0ZJ?+2~BCbpz?a66*{HZ{TDQ1XUhLV1AvMJ+Ai3*V?&e zF(R71UIVkq7Q+N!hY$oUy}BVLJUZGF&wr!2O?H1@ zrWGlk6M5nT+@#!(T7rFdh?mQ?4D+sG+D%0VEk!z{%8JO{Z0}rR%)}X}&M$sg83fdV zlI(dPPnA~co-FhdasITH^F^CByet+6_r98Lc8O_jzPkJnr zoRsy9@#F7w-}Z8y1CM)+1xT)5>JN`wv+1-C$#%SvB43nqeE$_})hl1kdyHJO>&xX) z+MAeoiu040hX0*a$L;JeEQ7Wa>8_Bq8gY>{q}kTD*n7_BSR_nLvrI(K%1iCjeA?7G z?Qr&0HKUJ2WooKEy8ntE$!F$?>hXK*3M7UnR5S_@(S*Zq)QM$FXwuHl%ml>|}8BKS8B93jf#xe-jCm(A&@xMc{O<`Jwih2UH$vRi9JdB3)F=XvsDV`_3lsQ zD@<>Vdm83X$4S_Utd*JZ;p~)UBIrYjfF{?(+!9lTPn3TX&&09?%|W;I-7AKR(9WfE zBw}h*V$Ds}YF*$fEo~gR++{NIOliNvd#fMi&9!y@f8FPop#R#ghq6Se0?m0;R}Nf4 zg_-AII-i2xM1DG>*xJzNIU6RSzh}d$Tqd>VeZs)m1pVc4Yx6a`4$yONo91*)dP2yI zrV1TWOLzTp*fa158TRS(Vtr`degf5UG6Ah2)R2GHCyqi!e>U|T1?W&eN56m* z+;l1dg08ENL7dwnqk_%4Gg2hwWhiZ3degF)&Ik3VIW)zRrV&B&a4^wz(;9mlpQBKb zmxlYu8s5nC@P>9NsHpsP#d+U3qhLn61hEGnrPtkWt9zx8t4s^$ncv}Mu8Jz{_r7_W z_c*T&I%vHn(M*EhcmkBM6=uv@*K+ML33#5jdxmY9O)_`}shBoe7c|+Af)+2P5}$+W#JWHTxxOGd0gb~ zI8*F{jSn~bATxFI6jJ%yw*8;0G)NEBGa87hTEqm4j65*ng%#=_P5%fQd1{V7JLz!g zjz#~2Y2YIM%G$^RSWGQ6)z61%SzW`+?zTOe<%{j`PGvuLg#z3*QiQ5F$* zFHTG|NN_v=YddUqcyVeU?3l>$4Qt!ntfEa?TOg0-v!n6+Pwbu_}GrN%RiM=Y&KV zfpcw%NpIlXR1SLje%k>n`JI(*Ky- z#J-jB$2hVhHLHh94*R(yqh0gVQJ>hJlrt^)N9)B}q!<2SG!*SJ`n%)2E6H z>r$53?x1QQJb%3v!YY_`*Kn~js+Mo5biy1uWshAT|p3>0w;h9 zUrjqfM|7~~PW{10K~ai}9bHvoUC7b&qP)lT$hWTJ@@n@gSDU4u@kSiSJv8%fj~-K` zudm97jNhJCbYs@0e&=G+j1~$q1vvj7y52LYsqS0*PUzB6s#Ha!cj+zMih4`$U}%DX z^d=>g&{U8v(tGc{*CZ%K=_L?4NDIA%nhQd=J?HdU30Iz z+mc_?UnbM~ND;2sxP@4X(S|DobM}Il_OGq1AV6Qd@@dHGLW1eXquG19>Ad7;w*#*?&ti&>5Zelapm$y##3v; ztQ{@BJy!HZpjir>{ zC|I9P;bRR~t>r|4(IVlX^+T+v5ANrN_l((<<07Mwi4`O;6ehEHY}d~E(FFJR)>)E3 zU99r;2DSroJ#8|?=k>pA@}KSc7ghXhxvc7;%T<^Hh=dN{6iP}S&orygeXuseEdu>`kyj<_yt+>2>ylsm& zGzi~=9zh9Vzs||afFXHlFAnS>U~g9|{%ga~e@xW8VB)HYRIIsLgh3GkufdJ)eCqV{ zbM(xN3v=Ec?8!vyzw@ZRI3GX?QuCV;PnT$BobRsrPd~DnR88_M8MI529idw!+89Z4 zspBUkj&{X$#+NjTz7*yiT3%9^T!C(hYM$&N*qHZdmys<|(`DA@xZFUo136HQkyT^d z3vWtyFXYCtCazUbdk=I34KKnl2}uZATd*=v5{WR8-K?wJ9-hT<-hF-c43IQ1X*{@A zRU-W6-@%_=O_C>Ww1BO(954f!M$Xh1awtT_LrPGGQqU5_CuehXJ%6zCfb%Z<%^#bC_j;KE$lsfzAiwz+E}LYJ5*6@+zqv9bt;)FyVEkg zLAA9Q!@t{4gFAV6{WTPh{1d`Rlc139xm9O?Z$6`&&#afKkkusZ>5?{1LG>aS-=`I~ z{KRK8H@4bB;Azk!9fX|{rEm)}DP8&VT9^L82OA3yE_9usyONzP-Amigt_VgRh|$n| zpA!Y0pGi{ZrlQ);ULBKKC%W-sVBhkTz-!6h7cjM#aqjb5SPNZgd81>})DGNUi)knL zPLWVkW6M*WoO}wz3{2bq+EEY}H!7uudN1Zq=De6t76HHSvb?{zhS`m4zGv@58SY0F3TU&9?_iK9>3{U`9yHF zx#GK){D0v3-y?D4PNXweZQdzTZPwlo)cIlppmcTtCLzi^R4MbA$d#R4LZR8&<|KoF zfBEo$cd{7-G;$<+A67|ceu3yc%~Ng~K)kdxc|diOng!WP@pGDs((^q|23eM83F~0| zph|EJf;U)))Mc(y?+K&fA0&;al&wc-ubS?5s^@rB)O#L>-#ezKhm7;O2AzH6^UgI4 zwHFs6`UM0%LZx*%g}3GhnmZGucaNJ#a-F!m7Eth%!+_Oytwz#n1*jpYr!(~hb@9qg zBaWCMG;6RmD>*qtwJMUGL_yItLpX#_HuBW3?{wNBZLwg(PDub~-JH#zRNQrwy>h*T zoai?2aBH-YqgkbQ|J_V6UQ`XpHB0pe!XjhQFmGa6d~eb!$gXGfiTAF(GVb@sA(b1K z`QpVOf}v-yWEfL$Nd+1yyGd%_1wN<`ZB(R^o=~*raELB7x z2yvIiJnE_7m|yoOpZOBk5$a+UDOi4uDX6c1@xd$(Q4b2YR%0ophY{NSi#%lz$A=H@N|!b@+H!A`xYN2uB4{`@2*U}bYvOF=s=cfqEGJC=NcM-t z&?OCpSQzy0GO4v6UfZdI6W8Z(OxMYRX-B~Z++y*HP7xBfch7Tw_ zl`}uLnGP{A)GoAuapD$5t}WQgZk?x0mG)Svpg3vb3I%6g<95c1jh0p);Hfkq*tT6$ zqfr1(lD70V(?&Brx&vhm);9sqHF#!w5mXP^^nXTUF9K)J`Vt3F`<=o^a<&GRIssON z%0+T9Sup*rvI_fLSnw)sNC#8#5qJe_PF|Cq*dh8~qL)yoaH-(73bxK_G)w^ihx&tG0Z(|vr;RskMUX)wK z)cmWgn?qW*KX++8-v9{**1o;fGESd)K1mSiwlho%Q>h@9!pq{*BiR_sXKP?_%Au(LkVpvT!+u@%zAIQVgUQxIyI5{faD zjNg(kqs|S2YGbG1{*zpsF7Hx)%{S9ESBB&_r@uii&u3w6_tagCYTnwATd&SXo-P-x zsZA{8aT=gF?|O5KY#_Xu84jqdc$f*XH@ke*E^t|xm+@kfZYjE%YY$-B&-Y3wqXxw<-N zn|lRNt{yDcs|{XyleFzbm`F^me0iVU4I+2k)yT0JIvSE{s*hIPE}u%reu|^)lbj4GBeQ8zqhg6LvlAgfbXn%_M+!Dy1nY!J z8=Bj0CC{ryP7PHy?qNgDzbQhia<|k-QgRoZE7Y}|tc0Ww`QD!|kbc42*nA5_&SBFV zyx+_XwY_rDfLdZrbXPkHW(@y0*RWkw&prXqoj0JzikZIax0hj+T160Zc{UtOHT%ST zsg3z;KFMyT8h@g0JdgIgfSF@*-q#SXDgmou4~Sx_PRb&R`T$*9d zi`9BFVGeFvqmb7^;j{;Re)FW7a9A3^Qq6tR``ljGoH$wHGMuyBB)2>5$8tJ+qA$m; z0!_UmraFRgieA__IG<&c_SqP7Zs{Igby!h~11m7)B1R+fJX`6GwlEYYe1TFqCX~W zQ;Vcw^vzMg<-$}j{tE8fTw(2bX&I!N~}Yo0s4FNtj9`$`2>SoGRf zSnxD(Tk7C<(No^R3#?atnJd?f+J8Eo-WGSym5RJb@7758y@`LnL}l*ti6ktRdf|Gp zf!Vec-Qdk|>M_LW++L@vz6Tc&Z9FGEqToyX$~2z(nWhAAkxapG^>RX;wKI{mxx3Ob zo`TEM0?;t$X8(CV!JwJY(Rh{ZKnwCgyPr$oh`_%T%mv=uHNuNMjB;rUs*-xW2bi|1 zRyCPU^)oRuxzS~{Od{>{Fa|!r*eP%%H~h5V+>@fshQDa^Fo@;rbmbQuNQSv$;(F$* z6h{aASSo1I$|?CC>}Mr(F3@-1z6hs`My+?bcgz~2Msu~_Ku!bKW=?rjAUmUwcac7& zV+3m+&txlFs^?5{8}@RIv=cioh27eFLXI?LmXa7n%sy-`ba+?xSR}zNmwa>2muCN; z4f~(RRRz}2EW);ncP(#Yvs7LWtk1v6IyHZJ5DjZ+P+BvF`F*{;kLT%sHB2hbdBrp# z&e?h7S_*7xab(Z+MOsaI6LM^ZN z?;K`Cquq$DP!UCiqqR*?!~R6kWM3 zgne~qbz%KwKmk$lsEgh|h0J%TBb<)B%~yH^z&3g5(NjmeBVNAH%qB8m-i^#1TA#t7 zF!$yZjvHz6-*l`Lw3Vdzkk<))NQC%$l%v!+slUgmuHZB1^OkpC$Mw(540Yp|mkt3h z1h(^gREJbGYfJ|HHBc6#r4 zV5o@xXOqI9j=qdjl~ty4sJyB7W}t~mK-~U=3q?qXuG9j?@j;$Qa3Pt9&p?^FE;C{9 z9BO)c*@2a)E$Hr~D(pONeLWJU;XCL!yI4!L&j`o_x;u1Q6S}R3pxVCdO1x^B?PcAR zz>PDW@q(bhP8i}xJVuS9Y?)vCOZ)YhNJuBXQSE=u$bU0X;CH%J!d(`7A#HTF?>F$>LoV++G*_GHu}u?! z3W;~|i)Yg{H9!y{5g{MY5n-Mb3bF>VOV{&3Gcz)6Sp%Ou7wCD8m!TM%%ToWId9>b; zPt51Gcol=p2*5m!D`)T^GvTTWsk5j-qyQfp?`XBwOT0+w(Z@U4;WLu+_6av6olGx- zMg;$5yRrIe<`!#E+aPp-DCuBu))lLQhPctUl@;hVK{xMijNU?)Gv7BZBw_<-iWJ~i z0fX`CW)jEJCk?x{KR(Q@3MdC3|0bP`#=R0)urR1z*8|wUcTVte_Cq+Ajw#~;H*MG( zIxYquW~`ts{U8~%p9Wqsr$Mf5jY}+X=PQZxZyim|e`2cM7z)@{L>saH$p7$p9X~0G zui`qEai#;=zcPO7H6v#iIxKBD^IJV7Cx5XvY}njOzZII1xg^ofM}8f<#$YG~(c59Q z3wCA}DQ<~7JbT578)>@z?Pd@gt9j~nGkW)0$=uv7RnaL0Q9I~m;_bhB8!+iLrX*a9 z5uZ~SOO6BlUg9o~bd}d&O?u<$ zT+iMe#3Z+z66hOarCZ?3iqv?jhKl^QTUwuSf}fHfW9hPUy%tQ~^$?AN^U?yl09vDC zvy&=0+$J8pq~c=Cby_k00RdF#m#dR2 zC6)W;zxP5?I9mtpSU#y7MbkSbZ^&)24XL`Uo5+2s7jN~TLD#Fa`~&Mh89W7 zaufP6zqY?U(}L|bjBjLSX~T^>rJSJMx7a;FCp3egk%_L);i7|pWmR@49JKoXm;5`K zLaPAO#d=j;SGQou$?_#krW>uKa=pZ==~4WD)VHv6vPe&>lW4VrkK5J|*=B~%HRX@I zZfD;l^NX#I0sGk;89wOeJ>Y8GpxX>g(S9)Wj@fCH>1|RsVuOxf7MM8I`u86iJ5#y0 z(ejSqop2go|Lh_3YQc_$}y!ULLXFY>xQ2BjC zMO@cbf{uWtu(a%DS9J9~lYkdP6aghnY2*vuz+)gOn< z>Wkx8&wuLqn4muvy= z{l*7By`4?k+}JZ5j?$FbM4Rz-vgngibI{Iy*KFGSI{L;ZyvOu&<|D`Yxf*eOt1?gd z%3<~c_QB7JWr{P^KCb%2_Fz{4KR$ME>Q0fjDgM%WWj}8Qr&+vP9e&hAic!-|3E-@p z1L0PNCG~t$+17W_h9av~S}kh#7%A8YbyCp6f>}=M?Hhon+6}GWRIS2)Q4cA-aQ#>L z5h(b5*$Orxe0$2W{jYWoT*=hj3BaGD=GdOA_;2S&5CytP6(4zxxm1C#?yt!7UQ(?D zugC<-B(qKg7u>xFrm#g<{<+OtBzPGdd;1W7eg@BtKf%sl2kP;M>?xO`MGGA*HLfG( z{LJ8k3TqzN%ZSS^bm^ov9vNV9y6K`w_g}dGU-X37VE~3l61bK98!DC)jTFw`%NIMY zpMAolqX$hjYw%tiP!+2f=*Vm%fbO~^fBk~K^p>R*F0BU$^TYB%{e1rV*b$DT2j9PAw(|FqiKfb$;ILSXM(_YM*~ zlLGUr!(euV)mNvN1IoAeLXksL%Y@uJgq&A8@|9>%hx@^rz-W@wm(BchiGnA~?Uz>A z?K}V1b%Vlf_r9QQFYYHUw7{8Ix08%&~Elte5b7=`)S$?LE zKN^(jnm{}PwHx|u0(S8@-%{A}&x_X0g3)ODH@IYIuQxkc0L;qxpnxseyK!``Bu&_| zUVvTxNr*tPd~MLxmg>L7~Fny(0-%dmuqjm2Z#naeH z14YXCzq^D+lqa(jFpYy53r$SvA7VG^k}$m;WI@{KvDBE_%35gn=~YKFro($rD20@o zO>8!L^0KD$a55}1UtqM`vbz;Y=CkkWARbObM6BwhY)Cd8Iy zzy3&lzwm&KIxCyIb1=cbQy%rmBomaGqfy;(FQ+<9>R;QXnVIz4RT|}Qhmh6!v-Yu@ zuT^%WQ)740%?>>`#4MB@6*Iqb%)tPCwEtB((_|_9Ov9UMl~-Ii0bf>Cq&rKnl_FyP z2jcI2bNo$JVMUF}+-|cd`{G`mb@h#X@P*1`{%v77p_)sa7XxYIg00td)lU`C2duQU zh7~`>O+RH4`+f2L{vZr4Pr}1rcYZR!sd>2)?CWpg(rz;#tzUV+(5|nbyYQ#MP%jn5 z*1bH}FD+*S$(5s8sg@8;EH=ouB%Ji}VVO71((`rd)%%-T=7~}*a)kb9df0aQ0$3>| zWi~yRE4Oai=H=Tu_t0jW+&m|Bugp1t!e#S1tNc)-s`MREkog)Q>%DUVcdBgReGx~W z(Xn>>J?5dp;r2Q$BeU(wGZ!w2iY?`7hCU@g+RZ|f=m241efHBM(Y&R1CC}GQ2~JZi zP2E{4x2|_Z%?i5<8ylW;Bt|vY*2_?g8)d&{uUGg)IDl1n^ zB<{^yZF&aSw_0EH5!O@)!_B!4Y_d*q?NQZ@&#whae5?-MGSt=TiyB|U_eTG;H)4Lo z2aCQpt45d4K2{U*QP8 z@c^zY6rXkTR9oH|6qm%|^4e(pd2lvowcC~xaIKZgXy#mTWt+hMs~8B^R%jZj)(XVx z3(SPiI;=rQ0g4Mdk9^+y2&)s zW1r>ITaFg(W)LKkSt8ReVTdqmsVp#;9@VUt!YYzR@WMbrf36;2!3%DeW_goLGxw#- zIcsLu(NVvLe-|lK%nztCWgJIRssCxmFy8w_Lq1BK?&xz-Rk*X#bvKXXNkdD+WRd#SZ>oU(gIUY5t1Z6@;F!!mXe5iU*kf)bZ_pt zVD4eT=jh2J{OwVxxhQq9)+V2iS}oxRp*Z#y>!E<*M=Hn92rml8pA3kPC$;dt+B0fK z*~BYnaTqVJYO>0_{x<98@^8Y20MD&Nmr#)@v+#A_9&x6zgU{$U5^V_751H%)2q?zH@D_hS+?;SoJfcR@0x8i zttY;W`-JGD2xC@OCFOI*UijopC*{Lv!S+Cjj)9n*^ylJoW|0j(lUU50NDSP z#StuRsTlgWV^;E6X9mcsS4_=_$$FYJK5v7B>$`EAIR*I#jP7O? z&z*R}12RRiaZ#Lmd*Qk7G}RH}5@ej0Eq3cS^%-yc!w72P0xq<{YJ(HUQUxxWL& z?#>`Mcy#yO!dX37<|QTqw)R8^0zK13XwL%uA-P&!eQHbr5<+KZZ-8nDSMADcYQq|W;?g^Nb$kC zWWRmP7;~;TO|K#?1~g14P7|1l23EVOuzb2b<2kDjdulY^dlhrS^4~9e6_4lBNfS+f zSorKDlN5)1@0({xASMb|Ovt5=+}e;745=R)nW^FX2k6*G(8h-1+k6a~3vo57CFrS} zk&3i$S4u|DjD{Z^zxQ`tZ**8$HkZ?O1-^nh4BA0dtJ#{na?*cf-@i(sQJ{8pvU2oi zRcJkBVD7Txs-U)=CS2Y1hXf;1(a&?k!nH&EC=T4fiF)e4I zmoV{>Zv>q!^3N*4Bl5Feb+;#IP7SaRrAhm+XUFWKwVNX5y}SgUY>_7c8Pl)Fejtb^ z+Gk9%ZKcZVduECRB^A{@W{z(XS8HdMP`u3K7qm|?#0&lKiJ(~HhARotXa>K!yJy#Z zw}n0+`p-|?)RyL02`Oh6uhQu+RI%bgWnLkF^K?sDPiN;=hk4VgeQ+?mxp816U(^b- z-#Dg;GQ({lc|cH|b{9^_73}Pa`x2}mYeuxK_13~BPks#eQnxuV__B|wb>T4qR%@pf zF=gscxnX-(*m1~q{=6ohJY$90ciO%=t*1Jr*nmmHyxFlCsBc-6hjCQFZlqZ~Cby3d zyBmVkVOxAqa#6AJaN$~)79&#YM$Y3-wP?a$oQhA9FY-bT==j5;5Bx(&f|CECLKQ**wWkuZ)WQ(7J5ouGrC!^e18rrfxWfe$3Xm$HpM3MAl*Jk3T(fh{d;dO`pp`2|D)R&pXH)x zzicc-;BSWg-!%Gnkq6}{(+9wxsY1?^!-B?RQBIaZNuv9w#v*jN+nnOcyD-1#6J3~2 zOYH+2Xyo;yt%x*E0Wmtvx{QoUNt1QoZj=A{!^W;=wwy3ysoCQ8>HSdRj$e|3zldHF zUOX&%{;k3$j!cZ8dW+2DT|OAuG`p`wu9F_?sw|rKHLDb$WzdaKL@8NIj^Kzcn~8)($FNEiVT_$dOW~2C_+ombE|CF%MJqXF^gcc`1Im z=ut1HSBUB?Vlq13e!C)&D(5BNbrLbpfMN$~r-~I-D%>nY)dwzZnW zLtui&Iq9yj>+GGtO}^zuU*C?s(S=Dunnf3%F+)Xf<~MdA0r!?}b1{8y0-;Pt8B2)4 zfOEhfxp3RqSWQ>^oIf58+=Dt?kL&Y}3UW3TYfO~Nvj$xpbaZ@1_rH8h$$N(H0-3Fm zAc%ZXEA8rsIM%WJvS@TJ%^Z&pmD{o4M8xJCCHdanrR> zse`#jnZuQ}Tj9TnF1kzYVI!E|k0 z@=m=czmZ7aV6jO%{eNfOu9hue9=XxDNq++{F+>O?#+A6R*^x+pzHxk97b>}$qN=A# zjV#F-peKH^YqdGR@JrS9w{qDlpbx_OR)le4SZ1S@_@8&eBi9jMNNjm;s_5hNVDjH8 zbh(v?YDOgh`!m14IF^#rv6HiC4c@KNIgt-wX$nj|GJBqTS5rb=*pl|_nYSzlv39kE zFNT?3(YcVnIUua!ruNEs%b;yaMrhnvQH!wVxZ4JgX{vl&XOPQ1NYZ2d$X$Cde*79c zqS9`eFjgH4{DvGx)U3%##9$xLZiTqC0GNSD- zj#(2Q4thd~BlXCQdpJf`kKX%Z%LgV!?fTK0TX1^+-7fzm@aL z>lTVwG(E#316FdE-A6K~a+VaPR`3V*Q-qhnnr~*g8Hk#Ekn!bN(?-G#Z5DM_<-!7W zmqquzXu6sy#tK80I_)!6XZz>&)nQfdgh;TzY=mWZ9kSUVoVELgO8U1p2FJhroB3y zFwu~@i}6j_VBvw<)^N1fg^`^ImvnD+Ofm~LAZ05N1`E$YcZ7W|UBO8KZiU?-(IH2g zb_ZSVfBvaNm1zFGufu=OrQ}qt8!C_DJ|wgNUjiqVCzi!Iv!O@4;vzO?{cSNG|G|MS z>=uweBy-7T$VeuDH*SC~ew#*|aFLp?}23-w+sEqT4_>6X7^t8ta!l8Vc zRB!SZiIeWlTTN5awk+0RLN5Q@= zs$wfQeuU{sn(*8em`c!^Wc=19M{df1K`CZ9c> z&p5yM-DG)f9~zr`)tg(Qgd?5&aZOQW-cCKn`e{V0hVN}?Km2k{___u5RiI ze_EAM7}u5)B{%oH;E?}_03B`=F%r-IAXfR}L9$K!0=#Sq4CHbz#U?D67Q#3suhesF zJ#X&^BWGh?VYyH{`@0f;n)q_gyi^l~MPKg*RC<~QczCsv-7^;xfLZ%xAT)|+bJaey zS{~>IE91JefHpZp=+gb(NH1Ncn(Vp2X_96Y#}F1eesY# zXV*9GqjGyh0V{ShqsHdm$#d@C(VQ1=@{6^%`wg)Gf3kX$OE|x{OT3 zTvp`n12%Dz36WTRTx<--zoLh8*%q@MzekmV3Y7#DR>@zmm`ZVZM-lFV+`s%NdrVwP z`EpAwoxz|+N2uM$P(|OQK%lzkwMu`eaIMD@!2)H@PIAkP58;{@y^8V9uAW@2t6WF7 ztq-=DW{J-awQlsIBt=L}#KzEk?=V8TSaiAm_w<<7w*&tH&Eok45^UXw&$Qq<0bc>h z!ETO|IFE|>wIeW%l<0A2Z}4?GTw}rKqC^DvYShpmhuAZ7v#Ex#&9W^|DQNpSoNH(+ zK%@JEj`TpL<=#wA?(%ivorL+vlfB_6Y!B|}wYKv0>-mmzNO@YZ9>bNO^k7L;i@<9` z3q%#i6ivuXw!o!F@|5A0g}K2N@5jZPIF_AxbyUTusr+M6*mRNZyENyYE|- za+g@r$N5|U;L2_}Cwgo;Q{CUJsdu}w2VJS51e(Asd*Q*h^FCNVQOS3wMAMEf#| zeYRc7OZPAZX3Z^pr0+@L#r0~|&n{+1#h1JcXg`WZy)@ikPj*U#Lt3y8t=J8Hf1f+y z#74b^_kXlH&skx9Tsm6xXW%;aYKCS;Wq!X5{yhB-J(^u|x{1ySIIP~Egd1 z*Z#}$3h%zA!_9dW&l9zLL!&$)1aU;ahvgX=_}^HDK13#vOj3Sej5gW4oW}4y0YX7m zTnq~yx=s>P>MoN%_^CqmbS~NF5sGC8;3DN`4?(dR#5mspt7&6w!DpQDt7I6)8*=)X98++ zxe24zcT>0ZSZyAcWw6puD%jYYMK^0|}6XRzb8mn|Y%dPk5ySo|kn zdOdq8gsS&sE5!C)uq4DZOS9r^a^u37)ovcmsnDpKYC*p8d%xhPOxg&vrTRqZip}@J zl8;ZS{2DM9PU3SU90O|nk+U}?(u+egfHSPLlavmA^M|02KUkWWHpNgavpO6Ky6ueD zUAk4RCai#A?4qOj$QA5Y;|^gMN`d&y~cs4CO%u3aa>C1-!-zN%`I z@vv-6b?b7)iN~w?Hji~dAAG7ni+1sopv_%QRBd-**L}R;8tci(gJVI7V70rbTL!$~ zGN)xZt}xBg8v6B`XDc<$vIKe?!-nv-%<3BqKUy9PH`#e07-Zem=NJ9oJu_>LE4wWq zXfAM5tb6q)n#w|sjX`LVq)UPV=8)uabn+m~J*;ztK&R|+eV$TD5K#V1Aw(>J zr1%NMNbXB49Bk`5R9{jz?FG&Q^r1g0i4Xf5uW1OBQHU6#-HB}Sz>OHucnS8b&v3N0-iokiGnBLHJmS7u@+?y7N z0R4lo4xgt*DD&a$lFE(EJPfhP!I-1>x&gB1!+SF@_AqZ={i8qlol%7&t;@xL)N(B_ z@l!ceT2iSKsz&`N5UriI`*Gb%yHw%m%5(Q<;ppP0BgH&%=K5`@YUmbJf0sZ@_x#~U z<18(c&M9BBKiz&ir^v@-TOWDTi)29X;lJ$)Pg~$S`*<4wd$f> z-)wRhkNr{G{?Gcn{x<WpedR~>4oGz>INkhY5X@I(RLptp}86s z9_Uwnqqz>AHu#~>#JPEciBc!Q(r8kArIpY+;yuEGG5iqvFDnHyHfuzPEdK_^$1UnB zR~+kj#ay0+VDb=wR|Q1-;1qbROmhSz~BDFB4?Uu6SqZvgXM z@^0;)*vbBWrNEvlYq_Wm6C}Oo{3hjofsUv z?B!n5t=;^3ON)PmeGZZNdinkD98To*s)8J69<^D!r}x_izjB~3Y3uir(Z;}X#ivXa z00W?c2{KWV!JY6)|3juqqn6Y8?O&0q@90wjmW^MHMy)(EGZ^YX57D4zvNPcJx6X^m zko7P2xk*ZHmWCt#T(&J!pjC&Am4``#5!37jL4eyODl?d@h&Xm)0 z?%Xzgh%GVwh#hKrs<&N}7W)1@h!u zB>V|#H&y1Zhyq^`^RqroHa6z+*@BFer&a+u#S zEal_tZDi^!O0R^S$N;A~mh;tvl6%$qR}yxn?tjEkjIw2cqmHI$2(OwaExazF&s+FK z50aUpX!X}j``!CtJ~`4UDemg%RYvq{h<7p{QBl6YMc|(Xj6rzytr?mC}&)q*TGzaOw zp~XBOrV&@^y>WL`I7{P%FJ04Jc^^WUN+6gmil^4if=7Sr);ENS6mGQLF3&RFqWr z2v!PZaW^zqAH_=2$eUs*&jo0XJ_Wmj+Ve}`#s!NNx~K@5^rmfIkwy*DI{`p+0(EW0;g|{9K5l4-jJ;<&QFVS z@|mCr=pgQOSoki0E=>FmY9+5Ea=9j=rHPD{el& zJk)k;^Rw;PZNN;y!n?zUC8rW|L>dE2Y5-Q@-MjV|S$U#pB4sAWy`y>K@`bcOluKT9`|~~TM&&VlT`@%KtxrF>f(m{DR6F|ll!bu;oOI1*Cc)mP*PD_U6J;{xaw>QfNw{My+MnI(?__68rA zaL{?B?}wA$tF7L*Zoap%myHEiakvGyVwG3H(SJ>*$~1krS6#t@3YX7MZt0FV{}WEK z1MYs2ubQ;e3Nl%k3o;dS7j##+wb*PL-ac-4@nj2=#`$;7@(<2S89*r|)mo}93e(7Y z(*g_A)Fepz8D?syTSXOMmlRn>1N2bL`P^I+LKQ;Ny!nkgoPRq)rtvAqNWXM>ZdNC{4Z*Z zA8%#vY3nyj3=TZb|F~!;@L|=YTk7LAt!DODbzS2YLB_(cuo2;durO{P5yHe21*4fC z*Z{5d;j^K;-Hax?AOHyAd%wAuI8ju!O6r&+ z$Y`^c(mb>f$~W%;>)%tkIKwyu-{}(0bB7()IC}SebXDqmO`FuFyG=R1^RvWb`p&L? zaYBIDTYGvSGF|m`HU)!%6-)AE(VALJBx73CA0p}{=_B5O4MMR@42lr9h~~7lPtJ|1WypKYVxZI!`c1w+EH>ULTg&iIvtIZz z16^Y9sH3N0rvL1yUTiE@*(|A}SYb2@}GuhwxnJqz2Ha>cg2~ zV%l2H!MFa^usONM-bSG^vD?os)kUss!rk8X6qA{gBQ4r>gP-eyUn2ZSi^HiULu-)-gx3YOJ>wL@@cHxYT2xyTf8~QAC9fl@bq&esOC{=3l zeCex{Z>lGdFciEnF9b8;D13}xfL~j8Xvt|`?n89NrZLlRm(DU5M>m?)7&YVOStOSV znANt{c!r3Aw2K7C%oD!68kqX^{`uQ3=WNi&aDEfrS^_dtP@T;{N|VEsR|$yZbzB@} zxi&Dp`wZmBAUTq}*%(A+Q}MwG3Fcl*xG^w6Z@CSOS)i9fJs7i>rB!Z_Z{8QwF0 zwERk@`0M(v4d|!yggN6q0F-LfPS6F!7ZlG-@N#4jj7~>MT84n-{0&#;8vHoudeJiI z-jXckYGE4fgCaLva=QiRVQzF%XV^%5AgI~%*Rm{xWGFJ)` z@B8_?AfGM#bu?WI;^~0Df1HYCB{@x6jvrRSa`chN?#~pT3VGGW9THWx2m%)zE z7}Wah<3mvx9v985A`Z2_>Am8|fC7W*RxEq*sI%#zzZgP$vo}2qFWCgt1VzUFzcVtA z2};34SD-lgll^A&L*%=kVKY_fp*AE;p;~%ZTWl2wYx>T8LI{yv{;>l8EQ#1&(k`9) zhmdjca+Xk6Nn3sjO7A`UkVN_dkag#B5l{jkh6;3Dmvp#WUYe`%b?lAmuGJz_s{lEu zy}FwKpoXZuo5~+6p&YI~E1>3A2B7^~`fWQd(FIEVl7fVi8zj}a@Ysn=-Za31r2ppW zmsCs7cm78U#yi(l$3jm~HAR})nhs1e} zfINHGh-7$g1D_^v)~)-{+u^){xcuLs%8eW0aTEsl9o$huP@>JDOZ^AO8LS+uZslmy zHw#(_GYdTr^aM%N0=>+I_XZtu3gLusCLyybSS8zF#RH1_A1nb9_!eEG0ZAkWz}q>4 zhEv%DxbXJY+<5K&1A|(=GF`lnk9X-@h`w;bsy9|ntSLATHR@pk$zYKQu_9qhNEZLJ zHp}JmC4Yvq(vS#dH97LriGrQ-&n~Ai0N2)BvjO*1pyeKmHRE!p;tIHVNEE1TcN{&K z>XVsppOsh=Uj!8-_i3fcEn{>`3W^eLI^f-GbQl?utAd(}IG-PPTvd=Hi=}3!xh`KN z&Ao4&Xk9rgk-2xZ{C;MXf=Q$aE#oq8P#(w`c&zHQ@c-j-=6Zab9SJH1)MN|o6Q3HJ z$UUKpk9;*N+@=u_nA_i4n%!jHq_a=@x5%+WGVd^-j6 z+b(mX9EHj1cIL~Bu3#*#1j=${_Ef!Khwz)Pxf&{0&yO@z@XNlL zyGiH}j}YXycbntW9vkIq#dD2T9{wJe)Q#pO!L)i#EWXEDwka(aKBGphZN8O;IS7`6;_^~yknjEdy?Nk@RpUV>A&a6h z_HPfF7&}6qL;I=wAIKtX8Q%3ux@SAtAwGa0d8Vo+PC<$6&t9qrjM|f;g4O-C!wd6V z(zZ{6Rzh|zONg@G3=(q`i%D}OgMb*4u6R9<$v8URON1TyBC5bml`X|t z6Kma%ekCQhxq}T|d`&Ni4&6npx?Zv;fMQ3JwIAWWVhf7O zEHn!-X8EK_h|Q+Dhm~GU#;9qe0U&p>>v2`aSCOL}g3pfoT%^FapN(lvf;eXfgib^> zi&8y{vx>8kb0$fKWh^fao+TSEu4`aAO$b!R*UN&Os%f-_6KY9bC-)JwZWp@Kt?KTL z@*|3D!FIBa&4&uw`taF52Z{k}v?Y#CFVQIwOgik>`NZ5T@}HhN&osEY?N z*N6)XWzSW%ajl?2A+Jq^t+l4dYC+OMBDT9j^}YvY!!>t0KBhf{t>GFIoD5C10)!+? zwEOZLu1}|zk3Gur*+TG(d)y<|NN$I&{4O%8DCmvN%Os$$ zlM8{!je{z*Wpj9Bny#{y$I$iaU>bER=5d`R;;F~Dw&c*Jd5Y{D)@uzQ_y&FPFF&V$ ztHb}JEj-PNm0$qGCcUhQf2kEegQF82@vr7rV~qe&6}eR-&HRreh;q*DHl1J1>T7H8;7!xAgPtlSEWgMX zMP=c^HA(z@?DIQ?Nd&ZE$N29n^J?ww54b>f8390y0Y_#-LWp_q=f2X0J?TpQA9EE( zzgGCqgLTmqUkoCM|hK0%5`beiK!BbCjsJ8l&P3tZuq zipmfV-&SOH+m!2sqjt7&?lb$!{tc?7c{Jy)fF?v~rhVsc@r#h|pXv*mZlO&KFOc2O)r(`kvPF zt7XlC+_A>ZL&sc3TaUxRI_#Ft6M(NGerANiUQ_h!CqtmV2ebHAZ0a@gN{=r8`V(5r zbM?742Vra*u}A)FiIJ26R44B#uJ_N6770p@&jEv4X=?dR$mz=0gE&7sR3Fxv3$d@b;m{YtC5-bs%5)6KJ)g=d?O z&x!+^zWr+y?1zb*$T_>cxV%NtZgKaUMGw%#HB@~zV%T~{0c)U&`oHa~k)cII8N^DtA~^baC2catN^S$7v^bNUU?eUoR}w zdVj(lmC_>;F?8WWHRR*v?1NOa`YnZ>o%U9FPbf$<@;v5hX{rc{iY`$;NP_j|OHH~| zKjgwCMZm_+T6!(}hnI)balWyec1$t$XE!&+Wloxw>xBb85t5D`b_$@7u>ij(G0Pli1)x z18}wuu(+pU>t*|_b%1sTo4+PzYXH#Idu{$ylqb{UL?p9O?p8#!GBqdj?Kf{3p=ew+ zX{$JWYBn+n6N+Z`$6PmMP?fDbi9(bPo$rf#@Zwh~Vtf0sz32kAilgd)V{+!cyHsZt zjYd!-FeT%Wx)4c{NOiqDt4TlZnS|m5DdFoNn6$a8IO`4=!5d|r*sX@C{o8$)9MBGF zMc1*}VZm3SHf+ybe%Z3UvXGxA3P3b^t}t3T0MOZ)Reyan z*G;@XIX|D>0ubqrx=5Q|MD86A+@kj|7T+S-=kxaJyUVfj$O&c-||B86S|(A3wXc;m34mE zl3^SPNpI_KGr3uk%!`jxd4;fM&iu-X@oMHl=9E!iTplf#R>!4X^J?1Y*xR`82acVty=&C;7l_O@c~sYLq%Q>*vL(msYTI6pNzl zt94f_HNiWRr0$&V>CcLB_<%3-YG3EnhH^7R@mDi~bz50EjD^7+h~1>Z?ktjEp$^0M z52#s4xiV6`by}lZtEfD%kf@H%s^C{}&zus%z)5Pc$tq8wyLqyb!NY{Ka=iQ*yw3bi5>9yKnE4_GgsJ^#x@2J@3X{QuZ$6_3hzWs7{zA`~b zL#^qy4CzHnE<@&*-utaltTpu^V{R+i`Xxtki{OZoFL7VuZaTro@T~y!Ju*Oy0;b+6 z{2llII6+o5;sG>L*mcv#_3FlhsINyQnAVk5hkZzlX4)Mj35h_Pd_x#2yyy=f&EnaX8HfCHAP9JOSWq*1Y`*x(ZU0a&EC0DRjG;#903-FJTJ)QkXm{vFO1L zri*i-ED*CkEyrm!niA)y-G?l?;RLFpLpZU18x)bOrmZvt0IX&fILiE?*rp8USRz)1 zJGCK3b>%NQ4shp+{e(|6zB__~tfL^eD8Z@liU|7VIc^E{&pDzt%=LA)odHa$`haPR z0S+1&TGj@zPyp`@D1>TK@e0cawshV_IfJ{BRGj+ASMR?IM-gbOGPRx&m$X&zi=k0UU29!@qR$TO zf;D5W`fyoO#_iqz)JTWpOkHH;Q0gQm)lnSHq@Yz_P9GO1lu+BRdpjtn6U;AFYLVo6 zBbU9Cw`jcNAp-L;wY1DtfkfrlLHgkSgi#ua3x6S8q&8pHX(V+%T9borr&C2W6Lx~o#0d5;(7{^(zoq)rY;H0-xE}ZJw zBxmQ3Ur#A#Q;W0Ia*Ma zb`wr%4)6G`G-wyjmd!#dvhJpNmBllS=38GKEp$MLWhwn{*01@*7unbjImd*g%X9oU z<`Cv>F>)e}|3jAiA0+-mNWYWkCV*x?D+;LXT2<1?!lox$?&h2FWyD`nZsq=e%PTUo zF90x)t2CICJ^oH`F*c}B*K1s1}lr{Rogsa1~Et*t~I^t%pqRt-&5%~f2 zYDoo}D{2!ts0JN|%4l?AwXt4GWV?ip|CA#qG=SY_e$^eQldy{Ss~y@*()br8o~=h;;4Y|8J)?=|ke za?6WJ)3bZbbh)tQ)VEJ9HQCpM0qd;fJEB&&`KQM#O%YzhtUKU|1FvB|5N22KH9(+o z0B|XQ^>;{iVpgA-8~(9EaomJT+|8qPht~|YSt>5X&CNP55|1|7B_DKD{^5jsRY9n|1$#>QgXVGDvE1SVnuMcuipY%F* z?SNA(UQuFoyz5VivZvy%f}9s-#h?!FyJdl$*>t*c&UA2=2T)E+r-`$#w0`Sht^6au zs>e4S&)o;7vRv#|QGPxS=qzir8L}{I$>@iiuXVaeV8NUS-|tSzw&~ywx~UM*NI@i1 z?X~~}Odzb+J0$^6Vkj*at`&$X-$%Rd< z#+B`f2`jNW_EUdyJ={sP9u`S0Lns4$ghdc+%WLxUCQhkd33akGx&h+P6w&OgW`O_b@7cExsjE)lu@2V_@>OHybw~gbvl*5dm z?PPyc4U;}pQT1_3$^m65j#?4UVh|YKNI!T5##XA4_BhxP=;~B0ac%fAbB?8q3-5JY zh-}!yt^6WSoz=wSK5m%qfEgk!0=5Yji9GC*mVodU_gj%Bfp=Mu2cM@IZmB~pL4iTH z_;oi|^tDu5YT6nNy59C=^KWfHk{n7x;k}G1GWyk6ic$OZAuylS@?!UZeZ1d~JoF0< z83y*OpLyQ`Xy2HG^(EWNH>!3BLfG68dGZwspiwWv`-Ecmp%8>L|{Oe`8&26YYAP zKpCyH-Qfs0M}F^!E=7kT$B`Be9h>|9##D9zTFA1F;?Ij7Ne|TitgSu!cyhy)+X14K zNtuqk*9_DB3a3~8!G!V4lu!^{I$U~cC&f73s3^y_szW%-|N5y2a&YjA&tc7*DSsrS zIJ1*9ec03bes$*M>B@qCc-LCLkiE56vEb4CozuQ<^#_K1yatT`#4k6v!igFr@-$tf>lkV+-dc|PKwx0cCKx-x*{m*i^5)>)9P6s1ulweD7kVz5D}5L%n+uIB*|QQ1kPBRKa_b&@$es-J|=d z0n8?MLXUs|E24Z;<~A-K31<(flcO?_8~?06?89jVY-6!ev^D_7Hs}q#);$7kyY5_k zccW;q(?X|Tc~+9&r==&;PlUU+Bun0=6>?sm{_>LIALoVK0pW#9#{m-l)>D+Q7A49A zxcWAVVf-4(upebRE^G`Jb!hClzdoe6TyZRQ0ZUiJv?4g_#ntw^u|ZK8RGjaut{7Dh zUc73m1iyprrhCGtJLN_LdaF`$eRMzH|)EghikQXg>Ha8 zRF~w9xJq2qjSCM@+`XD`Z6M2w4&`~4qP`~>#k&jEu{*Mg+%FW`D`l&aaSXVin@-a1 zR1%oWYDA73woRjvfnxsX1Ja^5Iex>;V*5@RxD-o3>?>f0ufjrL*COTK6yb#8J@PH0 z>dsLuvcd7(E zQQkz~Hk@G$-Ubx~TE-5j_mTZGn(uh``cCqnbGyM&$Lycqre|bZzdo+JrIEI_`c8!* zjLqdHu!XQXB(m^JXotKbLz;9%^Cdu3H4uWKyzMX(fQuDjHtpY8+n~=TJQ5{_5)`Sp zEZD0*%iP@TdYLKLTjs|d7FvalR_fR!*Pmuy)&9C34FV@{0b7dz?Vu?wvTCDdeJG@v z2YRhWQ?8zGsU-%;&TgWN;Z$fW4neyQlZt{q3CO<{=ENhC5oLW| zR^MFfQ*U)p5l(I||Bu^9v*CYnq z>sKl?tzP9Wa8WZx@yt=v((_+AS}RK+P`6PE!2uuT)XL0a`3IhQX`vSj`U@snT$X!q zzPg!=8Ul$&2Cn7_q`cB86xuf5@BgtGI+EfE5l*OtVXBR3NSgZ!^TovD9gecO@5ppZ@uMVQc~veUA@Mk(G`ei?+KZ_fF^@+M2%}G>-!aKK}}mT z$-Pno)1S7FD_D~WHG^z>6mZe)#}>s{y*{~vLUgkbPUzqA%k_L^ZSdF=dYod$eUZG* z{DYY!YAH?;s$AKJw=K?!pV?Ii0gY0RV5{YFMHGPjeCaoKH6bOzNu+81^GzLP1LDQ1 zY5*?yTkoop6rj@y-Q`KbQ``##SccFdDmtE;pQ~}T9*p*vh+I?E%|l)>Hnu}S7&V8P zW0>)XZ0441n=iSH6!_KQ?|$m7kWBc1rqMZJ+@P@E-c%A!Tv=neY$~rE(z)-Gi2dw4 z+T>Sl?v&_B#IhFpE5M_OqJxkaGeyNO^5sOkV1cvaGX65w6IGpi(qR23FU+Ho+ITsk z^DJgyD$8>sjWT0i2E*oLOlDLK`TI) zEfmoP%1yyemzyz7*s`!|EY$J1(+4&h@m@O@ygk}#?5#b*i8lph3GoQITX_Tb8uDp* z=Gaq-aj2K9$CKaJc_>6tjmk$+yA{64S+L_~9yt2>BH!B0fUG5Pc32gVC%IJW&l_0e zw{l?+Hga%Dcef^6KET1$5PI_DB;GiEfY*wDICg;}ngMec5^fr!NTf5m{zvF7^OA+Y z&Jn|r_1JzL@n38YS|Cf?*ma9BnU~v)28?BOuZJZ^zX0>vs@f24z9J<22YtjF$*oIGv=7OO* zG{z;53o8MUNn|xoHXCZ5JlBdGkULu(ZaRS`iT{D-2TDJX6eYm-(S~Mbb?heaS1vUn zxhe(e!)k%RX1(7ShM$W+mSHS3L(=jA>)gSN6tRG^-DIjz&fCbG$=*#~W)s@?@ArGdr8zVqJ zv?7<;d^ zg}%?;4Da1k(sNvP3TI06@Jv*6=~^;wmo8?<)iMP1+I-OlVFs0gzEs2J`^SJxgVxID zmLh56;;y<+HKFq_?$@1lAxP5LnPL3H-#My`Wl;Dp>~kRx2DPE_Pnu-|EdIfr^NQ5P zb_8qZl0=I5`o0bx>QVcXrrZJmg+QJk>`r9|zmn~3?PUd5E+zNsa_$o)_M0g|{0HsX z-Z&xF$^cu(wT&5gQ9HDhTwqtKV7U~t_I$*RN&vQKCD>5-_{i1iA*zr)yOcR+u}LpU z#Aj%VQXqL4JEC?Tw$a&RJ?yJ9Y!>7!?W@1o=&r8!whh4`VpJ_)mhmIzs+hfGVO-?o zIb9R6T0z^>=Hu48y0WsR{o#;90YXg=`a^G z?*?UwH0`4j3ku5v_wMcdI%DrAnjfP734Rr;f&D1z3**s1?uR~G z6!U^$y><4o$Y6uMDg~UW)M5I3ll<%qjLHklw2@Mbj{6_}(VZeEq;&|sB0_L;Z(>9- z4#V8|lU&gCxNNA}qdY)?ms}$a4i*~VP|_+EEP@oCiUbePPN>;VBQ^beil|T zxpB?JzHJ35L!ux_cLMYD%+&gW1{v8FSGY%A3y8UH)}@)0eh{Lllg*r)jdG?A=4eFy9{$YKe~xSvs_ao=)YNaptz^|wqnF8 z&VaL09cBlL&(g3mK?oYW`Ur~mDIUI8#OlVLS8M3JvKK69u&Us$Zu3WsU&4T-g&no{ zINjKfKKH{uF9F6&C0)r|a<2?>xwK0?hF+mi8O67D66HYk|_6N zW%TeEPqOh$YxvOdVP5a`QhtJOs?=k+fv2R;_J%LV+~qHM&X(u)^QZMeN8irLNfTd@ z&lMud#n#FfhDNg7Vd~ms+ntBRf0urj&r_GMODEASB%*?>`T33%9>A}5F?Wmw{NS! zAWLs$l2z_CmaKLIK|vf<#CI7(eLN@`3?xc|wT|w4!>OmO9KBa1%&|I*I_WbEs{BlD zNqQm;>ijFwhE?tS>f5D0wI7bZ$ZH#UTlk!Mm;BqtD-&!fO zEF*g9Czv?CdZ#`h+Ot zZzJl)wOv#D8tV(KdG_UE7weP_X=ojYra?S|ZZUwnQuVod#Lu74 z)LE$coktI<4%->eVs84;uFH^te@~PDM_+cTJOM0H0SpYM>d=z2nW0AVbcCqc5QWIl ze=b1zFIlKppcj891p5Uwr(UKO>l?1yfMCmc(TSf^)b*jS91?P=BUj?6W3i;AboSYC*!P3#w@X{a)xvgysowuY50u!QiE^|>_a%gF_C4eRD^7LL(9LXemz zIVk=*@EZASiB+|emfl-)sEHJTN+ltW&xa{|mx&~c#8Z&vH1$LJ4B-|odg{dR#O7_8 z&Wmx8>03ljN@d$|jGB%3!MZkctQXewP~Flj_ZxH|j&fUQ;a}Jv+Y|1jcg~UvR1*B$x(|Eublz!*RYjJ>Tg&P+30c@uuE#!&0fVRZD zW+&wX5|dEO0k}{xBU>=YfAeeT2c-|XbRarwI&pph~o>S<*XY)muwEh4T&5H->eA9{kk{wm?D3x@(ePi@pqTvB@<@ z74l+{t!?g|PQxFK_DeQ%D`H|%#A=O%Pf2CG38STEmrJi{nR2RGiAYIHj*0hR!5v0L z2FQ^43gfw8)RgwY3EhD&%Z^_C-{=`u7UDsR&wYcZ)f~U8{T52ilqawcTstC23Ghhu zA3oRMROvIQ3c}Nuh94ChHQFU@t|zaOjQjtAC5k(6yZn$}t_I|Ycm_Y%YaLhqML24p z=m~!#U6aR3s?oNTV_`#E;Q~)pVt2&UKm-4jm9l?M^aSbI?K5%6jjyX8^vORrj*y*@ zUR_B1hh}EWOn%zOaiX}V5XDF{DXH?}ZvjuXUjDCk-8#=al`HgfqSEGZ|cUh;v7 zm_V+C70&~eiUMZ z4RNu4%EZ9;MMx5YLu|O2QITWy8-hUzPGyHWv>gs_sU>GRHs85vsF;U4(X#4iU9_Nk z_{dhCfhThOuWf>FDldB=s2=N^!Q8N5j~6F(hI00gf^Z&T_Hxj1Gw`LVfdJxc;G={$ zcd2*7UnO?uX_D6l+{ar&I;E#SW1;`K?=iTptn?hMU9jt2siBsJ@W$@Wl}M#0^Uuv? z34L(TpQJkNz^TsxvbrG=+zZ4X%2?h7)qN<#BZ!wElX*_|gr`W2mQ}N)bVgLWARZM6 zZ9s}6mi3!T<5_;dI)4?nA~WkIR&A>~CRz|}fwrojha2Ax;z%fj)TXW{1=TP`;Wt;{ z-N#9>Y=(ym>s#EP_OJ#t5O>8{mkm9PFf|UmxBn7y#Qo@eK}Z8TE?(D_Y7mRX)7bEy z005S-k&a>)yRu^sN_|Owc5%N3iM;ld0sF0N*D(HIXE(}yp5o+olFgvT?T{C);9z5; zV(c6k;BVOP0(N2oncAKVEcGnCXyqBY4@KghknVOBYj(c_B?mI$@9ZCK zp?l&;ff2DexAC_@Rth=zlZn(U7#-;kA|YJeCfM&;DQIgKzVa}>VmLY?2v3zxs#cH` zl-!e@{X#Gkic*B_xReQhlP{K%dfQbs#A|m>Dx$L(BAPdft3YF^Qv|ep_DCR5h?(v~ zBbjXY-q#D1wSKoQEr0V! z7d>cqI6n)yz9a{zYi6aTz3^OhZ_4CrGRQ`+_^Zf~m(#*Z)|X28b&Eo)x3Wk(ULLKW zmSb{sXpYjQawmq#D@8yR3Dnjy7ESrUFmGKR>vQuo0ryCD-CCWe`v+L0t{P`US-K=x zkc+b?=dSmpfj4G^ruZ*^0p4sgNnp%azTf|pZe+U6!++v!C+qxnrtC`P&ovB3C9Ov~ zew}ymfrxv2i$SB8wn#ar;NDGQ$A7EXt{7mOUS2pG zFy`GV`nA--u2eg$BY$$=iY8xUrY>k|>d$GN-PpuYkXtcLe`?fM3D04R*bRz$h!ALt z@oFOI=u404DO)MV{TKGQ*l(Ef69Oh1Y@Y%f^XK^vqnm9b@6cKA$EQx z)Ok$m7kGntmwl|=0r3gE#CW0n0x!4z#7RRK(O#l|asuz^Vb>!a#(y@o>u)GI-e4lB zAhGCo*IV;(X8+Wx$!~9FUN-67(eyV`eSHKEG~vmgv+xsAU!<}cg$ER{)|a&3 z)H<5C*~ld}l&>yYYan)s+~rby6oAVXwDrrW{ONqq{@>@6XgSHLGTiiz9#;{Q(d*h6 zF!Y?q#56oJ;Eq;J8<(=o|1DQ2$AVFK&ubI|9s6{u2nc z8!d{9w6?KM@eOQcY*ZiKbsMF^gkdT?zQ*8#)1b3QCC^PVq~Uy_DvpWlI`5QM{rhQM zu62t>rblujp7@p53-HToX%&|GD#};@wf1m9An)@6aG)j$){RZ}=ddcgd!i(kwx0u+ z-ET%){=UFDRF@jLCVyVE+5WZbvcyPYhGqD*i9!A8%lWD~2}?0)ycM(V_qeBUY~zCK z*F^PLFe;KQ6aiSZ%X-k;zw4HII6n?UzkbKeY+b^Ky}P@!Q#Lib%}nAS6~%zZad2R3 znrU@?2m+*MT+xSyZ5#*xxB{my1#I8Vig7uIS-!AxS@=u9pxiNtmiKj51ub<=(2%4D zCt+}G-SBgWh_zd8?A&!X|RRtuosv2WF_zN|UhJ*8)O7k8)h#rGZn^nJ`q zO_jX=0kn%L1lP0^1(}z&^GERbnP2{OVL*1(63tPH4|u=$+HEP(Qq$@_;&T-BbN2;w zWv%Jvo+@x{^M8=;f5NX_^#VWv)7`a}d|93xcyhFXes(7@@-OOPTK}7m>qmT~=H}*- zAfHI=bn{}@64Y;-*^*%Vu-mE0WMR}>uW7s!|#A-RoN5J;S*E;~0 z$Ci&bRUc=>stmq{voKc^^D5q$nQ1;wLd%gO8!~Qoi`t?y zKcxC@b>KVNcYlbGpmBfCWG-$$3Tmf|90v7)eT;{L=$!I7Q zCI-LSH%l<<4ji<5M_Ekw!`+-g6GLHi{wjtS{Qh@#40U$CM1V#v9eI*(6(ziJ6KpK_ z=jiUdAWRVQFX@NRoIEs!S|pS%W|M)3@~mOHO+XcQ+iy0+Zyl9j!YW6GE&l4;Uoqm{ zYtlFO-?rg`UB8dHB}0oR{|`P29eahpqdSCNYmW?>Z^u<;*jhEe_^i zoWF8QiEAK|dr#(AyRhzJ0TL7MLui0?AB=LxH8Nc@90B~Il zJ$b$1r{Cz1?2iW>Nda~|azCa#Z_pW}iaI!K`^)JpkwQrrT%FB9vYH0$7S=fiReLWK zqzu1^6J=k!Uqx=W9#oPl+2`^~z9^zeCGq-1$$_OS+>P0#rWgrbd#Gejg^*v1F)L#( zJ*-!ulJ-RaeJqCAiPzf#l(}rimGJ}GTDF{qM|AMlnj?!o)7{nR-kN;#>w3STF}Ywx zX=_6~JklU+$Ca#?`2!q@eT0RBd42M~{YD=x)bH^xsOi3miHV8N!tdj`E2+)}z-WgZ zXZ)vk70Bw2NX!VmIW(efLmYpxFPX0=%LsL^cQzjLOB_=P?fp*RpJ{lU z^FfSI#G1qqRcMGGQqrvfh|b}YsQ;c&I84guBherGHaU6D;r0kw6)IM&$KOPWlN&~s zits<&BR+>Ka(tp>c=he@vDoR4c3as_1;&(or|IG#{4jiS(jm-l=v0QNJi)o^4(ehe zX*xOkWk!?T55=Wx=1Z3t^Y{4TPF%A4XP&qpyqg*tWPSD9+}zxAA+5RW7GF&BA9=Rq zc#{;>dU%`iA9I_A*#=nIhdP6sOCo z<%(YWcUXG^Tw=+Vzf_kF2&9DmPgrW_VQV z+++JaYcL=^$C%~z7Nn-Go;8VHzEC?FAM8Js8XWaa*jFz zEo`|`eQ#0CB2mHF=mR(u`|olI>1fRPG=Sfgqvq0v2Ae*t6YHXOO?~V(e@99%^~2a1 zju$P6N3$Y-`)ut&X*w~;t|8b#<$VuM{rB)wkd9gLQGvX2 z3T~%w4r={p(ayq~;{-xwuo|-ip!D`n;Mc*MHqznI`@mMcr+Tz`i~b7&0-qU_vvXd# z7E!ZJx^d0C<+;Bn9d1k)O%r)|`8BXp!BTfuliSJp zb!sjQe6n|}%4CUdVF|7l2UR!V?62ht&sonqmcLk%hHhV%s29nLxNHctISuyQ{*n^^ zgNq1$C?!|Z%?uY%ev}!`!+3Sn<;YroYf583=Z^aNeQIj?xBI#&(QdYbqvM~m#G7C3 z%%h&!iOGq3H|`fD>h*PF!n^AkD~2mRN+C-%l;np`frhgtq`a;__ez|MTylhWTCWp4 zUde^zaAo?LnPruhqOTzJ8BpjMQV@gL9czQ0twGR8`3xV9+c1@55 z1bpiN2ewVbX<;39b_^sO+&EqZ_#VnpJLc#RdOe(C9vkBC3`8(7sS^J8`!wlEH)m&B zv81~tS-iH{tUkU!5)w-lcPn1OrY9$z3|V~?znDs>Zu`H&dr77snQG=R@+o^=Nn(iz zR>BDA<@+G;wO|Zq#@1%FYS=i$1oPVOImf2s?q^MYPNPTtv@DLsh7}q|^QGPqk}_Xr zY99G-P+#k?P;MDJ+vpA`7#EtF)W#tND&v80(fs<4m4=bUG2m(< zbtPY`xaF%!Rv{-mvegjDX~Br?^QitU8giUPmO#aKMwnHNFoQaax}8nZ4r3*Vd-h>v zWkPtrhi+2<$2tP*EgM_HW;?}OPTDu%O1)6BW&Pg`4Te|`Ml+=6Dq@hOg4xH66 zWke4OlP8S11<&2;hwcvm!gtie$Cbyi5?2R@TZ^#eel3J8QJhaoT*aiy*eKZED=!$P zdIk2JyVe8PQQUT5FK~ZN>DV7;`jhGMMcF$e8`^C9h=lkX` zk~^|S#J+!7hFG$}Y0`@OhzK_&co&C;O+h&rN`L&b78T&_e<8lm1YKDiG=4Cpx4^5C zZI6SBcP7CHx}w-OeTR^7Crl9N?X5k_zf0`&A~c5yg|>fAcyrK`;qQ+}0dw@6I$E;A zNip8r(e}AbG72b2G2Xix*W25v3dGzYsvdgQ9>_Mg0Tg3t{J5iFsbD6}l6IrU7wk?X zE=Uh|4{QPi%gcS>siJhMZZ~TP&#~_*^Xxa-sXq&qlPO4j4djy`9%J_4r0|M{ptRwS zW58ucjp$c>7E{Ypzr7>yWHt6cYw_(TNMlGO?lZ~~j3?&k342uWCJ zLaDyAw0F89#zQwflgbU-w8n)G?05^f`1m9(>t+cYODLqi84woZJ0_$?Xu6K3uW3k~ z^Bybz@B{=UvW_eJn`g79L5R6xH(c!vFPnxyqb>(@89Uk1a|hx|)@cd+%uK?8A&ioA zb*37PYO;FpNsf-Ugxk^6%0InbUx$8qPU@^wSnh=Z(= ziwz9bnQhdVcw#_~+BNwpDeYUv$2U`YBK+VYzR}71@)u?t8dJrEdt$mUn%UmZ*M)?$ zT=NHRJz#zj^g>TagL91gaD@^&ffJXvu{_ssjkB&+7UH7JGH(@ zl8d>lr~o{sEo?w%KXb3IrDgawB}F%!#3qmi;JEt;Gn(BYap4w`)51s~Z^04jw03Cd zL424R-MLFYxwiDyERtj>^KIq}k|DN?r{=SIyBF7Rra<)B8Weqj`+(|#1fEVXq5esq zwLc>o2!)E@9Q-@93&A7afvWGZk7Q99ikmN#!66Z#njERMTg(}HOMB|}j5`s8LaqM? zvfnwlP$(HZQO|49utxKbL^1NrgFh-?^YOWM=@q>FKw@Q)Mh|=BNJKZvHQv#&0#I6r z2jMNxE!t7^deM>*TvdgAdL38(Hi7KB#CYvmy5eWbFd%Oicf2w`)bLe+k`1O1GB-G_O9~-cd>QpA0r!#7GbdQO0#~zSrMxk zQ&Pq&5bjQhXUz0lHq_K zxY2{EzJT@YNzdWL5(3^RvT$#BrCdqH0y#?orFq#(1G9-FT2fiWVv5h&-Zp$?UaQS; ziAM9j6}e&cOKqMtM3*r(pMj7-k>v~LCoaOrfGR94RYjJZpGEVt(uS{ytjk%ygk9s5 z*7nyAgoM2rYK0rc@_i_CG#KN1b+hDcrNC))@U1^Z1+q;uKF%>I%+2l!rc!v<#E&Qp z8%_Pgk9S%S(oSDeRrT|1>-8SZ;XnxXod#3?vn6dKajMVxv|5YX#{z&A31E}DXWuOfZ%(IW?Sct-pla{{aG zq9K8NM~|#QZ|?;I9|UIp;#CC)pk6ixuV4FoA9@aFc?Yihk#{yKb||#^e^0e(NdOo^l{60k!>x^gyyiFb`VQyvcfd8UbNv zx*d#I`*FTj?DK{d8Oc^Dp)VfNXmB3BFp>pdIQk>aG}Vo-#+Cyz4w`y=U#;u0P;j*LCmx*(??I0`%Q- zN@$)=RJKFLb@LTrxyuIDRAjNypMQsIO|eYORx{gK=#v&@U*Qi@?v&#uP#NUG=msx^ zs^f6G0|`p`Cv84kOIOu8CEa`jxX_R#5Z<@TV`lTc^(7mkAIa{)@zwoBIcSCfACl^Q z0on|E-26}b<7B3x#XB&3pSN9|^{`3X`$Sd0;Kh^k7uS4IBT-}VcWxyhC3&Iq;f?+$ z!-8zqPBRdi>zBFp6@RoY$wPyuEB1ZyQMX5oY_JP zp382lTzFH$R)SPZoc;9LxfZnX8+_=Gz=>9;TAmnn>JLo|NVEKd-X)gndFn%l$f_ln zc$Q4C19iJMnSPx0|aY5paAN z_ER)B({+>5FLYXvvL-r(eo2WMi4HoI5R>XzO)Azx*gjxR)M@h%g(*w z8}6?%cJZ*rlES?Vq6;-=yRbh2Dk^ibznxyA_uw;CnqOG&KK>wXo|qg{_8=ZM5?p>@ zqK-2g>J2bFhRi^^sG=rA~6lS=GM?_~a7VtJ-$$sbi2QBVC5xd<{Mpww)@xuQ7^75ox=N2oc z0T=N@|G#+7{Rhd5RKL@|zp;5jQT#MVSxsSt#QGko^J)KVd3FQEuclom8HxgRvUton zG-aUWW?@U2V+puhEx`o)DIN~Rv~IiRn+7tE8((Zar}KnC3u2OMJy1kHRv*^ZDuuGf zCk)zxw-puRpYU`^-iu$I4$-(YT13y=8<|A10=xG`fHR)$Q#)%ZSEF$y6qPz@9M+T* zE9^pO)d1oUKmu+Q?rAlJaFClil|4q{0w59FZlThzmQ^I2!=JDft>uSS60Ccp@6T2u zhamZ?GnGYe9L(J&Wj}XD7KI-4@2e~Tj>H2z#h0jIN2pV?!hM9mZh&B0fFOXubq7#_ z4?ZRPSwB)9Zw8&01rsZ2vz(c@tbIr6$%iS^BhO7%Tk1&d?=2MU7H)rJ&*MKgDEL}}W z)ur=%(f-EL5n~EOe(m2oAubKExjJawCZ%8J%HRrmD!pe%YneKwj97Cq_LsbDOGe?4 z0ER!mtl=zMaiz!)UmRj14gzg>J|`1mRFs~?m}4*yQ}BHu+sXMiud~|PsNwJ`Fb zqB)>7863(U|0ueMeJ{W>LQXs`S&+$@&Z=oRHxomFIYJwSSOXEXySW|?&D&QID}UOu ze#fcyp~yWJOKHZgQ!ayGU12w~X>t57UHAiXpL_fNAx~N(#_s_CS)8G!{e#>H&?UWY zU`U@dd`A=9&t&N3QIJ13@c1?|@se|tPZSHLiu{POy?r>+9xxSKK2 zd9cyL2&E;nDuwPRk8(++HP8l184-j3R^~Q$mU-`pr~3%wQkLf&#C0xf5&}h}%z*p) z`}&g|WK{NeYrYN|jCESG5umlz5 z$0SD$^6da$OYfxXg-#Ua;(YkBm6lFkmDUO6Z|A*Lo^3DY>S=A7?GHMmx~N zQHfH&CpEr3%*gCrohu+M09&hv%y+lcT_2}2lP}O}HU>UO1i#OF{lKxoX6E5upI&Po zf(FV*BUmr5YWyO6=#P1r!0$J_4103>YD z^AW=WP3nk07PWouj>Zv=8=lQ&A!MUFD}HF!jY7igZx5zL^lrbz(OwgcwJO|xp|K7K zZC&#|G!K|$$u>j3lKk-ScX5KQ6ToqVN~d#&jEG#Z;%#tk6A}y;d!`W5J2Pn znR-W8f|0+JhC$x%4annTFzb*KsZAb9CuVnlxG~&BVK6gZYd$ZZyyWXnF>VT!+3L;v zDNK?B5qi~38+G;ev+9lSB&*VUxa;H`aFSgkAqbtrB8z~dxhJF)0A|L0G9!LJ0ng#$tz z(|%G8?*pKS7C%FHN0)EnfqLV*AtC!(xo1Zkf%P{p9v*;aX=;tY!Q`H{2vZI9P(cDE znT<)lK&KFbjgqgsza7^Kth}~vDvTNAZV|EeG#IX5JKTBmO}En;RG4)>7n-q}Uz7;! z775`t3lyL@>~9Rp7)Ev+;Hy{12Sh@ClU6Za-pFt@y9n*n{+RWRPCqdE4*K@po2#wN z11Hv)C#-n8a2=`u%|W!0b3C&e)2* zbfPVF;1s`Hug|!Rc!U~59HO~-aAkduz#zYx_q8QubvQBoYZmjc-!~JZ602y!K{+&% z^Zux+&hY<-22JhIum;^LzDyqO(_@YxMRxZ8QCui(!Opj2*kVCq09UfX9hD!Y&zC%V z;IcKZ=eBnsLsS6C)H_v8I~4SU+gj{Y)EgP-0L621a@VGs)tbxArS{(HKEy0VgH%Jm z?l7s#j^Jb`kAt>qq4!C5ybqn)0A9Qd9;IDy6vF=LbZj&!-+q50QwzhAhCG>W`QdR{ zlXI)}+xz5E*%v8-AkfbFj^kJ?>#?(sFxr0jJOAsw}ubacXVECt>!? zgcvO<0oMi$Fg&VOb*L{?PE^7EKx>~r2Gg4k@SB~V@I+JJ%VfMRl{_7neB4}1{_j~` zW`9U67nkt%bj)bdj5t$I0>ZykOt>W2Yu&d#Z?~W0 z9PTpC_6sf1vI*g?+2|&sTXa%%n)asEgGDfWqkqMK@SB_d0xMa^?U-?p3Kef;WGY}s%4dVQg-mO{~#(OJQwmt=~dP%XRw zbHw{Kvhs(XAO4rwX8~6skYRq-V!(THQ10ha3h zd4V{-ouwOLNi}Yq+R-H6U(C6)Xt{P5H1YFYIJ+!Z8CJ*OcXE1~*3!bS!|(p;26`}= zCk*;V_SAkJ>}E^kjkUbA^chl{(oNI~+#U)$^$&MCK%YUkYN)14x#QrCQ^HIj{P>9; z4m_AL4j;Im?_v;-E}gFsbpC6TF{!oOU7do@tMOC^&EQWavO2qW-pn=4mBG-$*O`Rq z5sO|l8G?m44)nO%juy>Ej*X&!?jC3BDUu>zVG6eO{BAF_Q_yHd$Ii2#A*=mOUO0Bw z`wXDO7(9q8z1ye9CaU^fN0V=_YEM4cc049}gM577gSvZ^MIsNC2Q0z*kd!`9FzOB| zesjw!D>Dpp0U@Nlia=24=IkX9_;}k31`>uLZt%8O4lR+Jl7r|P`{IjzCrEu)>hs!c!N8I2FfNie!Ii)z;~aNA&OWktVXVfZ++Lhs~!k?~t_ zHg!HeH!bfQZxW%fK!?pM;N^nnS_8M67F0nW&$N>X?$fh4xmxA*t+;_{;zCaOxXRL5 zTfgCV(_{}#2+b2dL$i2M4dB3eO-Nq`N0Hd6Jao3X-?z6mD&}>UErja7txy$w6o{CXwF$ zr5=Zaah)FPpXCI?FZSN)`t8tDihDABup-S;N=*UL3huJ0{RJn1Ni9eLq?HVFBV_Q> zLR{aml;ZOEUGmA|_p;1}%~;1D=?da+wAjS3*C!J&XMFzgqFT>Obsg&-dS?0*i$c#j@e z5!GZkYV3fzuUWf~M?v5AC$q7Gv_@Cvm2B8sEfwVRa>@jdoi|ojXUp$V zbbrHVwpBbWu4DFwoHLaYYTSMP*MsqWlP-Xga23em5AA_9O12}E>M}~gW+YCzawP-& z=VC1Q&Hhgopy=ns+)sp3VBlL7{k3c9%dp~UVa}mjZs~iyhTEs>-HM(b35S0ct-<$< zlJmqXac7c`YmhlW`wi($OumO&wO*xp?c>?ES>S_-amN`gVStqFs9HKU32$V?Qk?-4 z88obUT@d%2=6M%{wQfs3`1SBnGxVPdbWt`;=M52)=7B6R^&L9!>?6V zff2u_im^r!hPc8eJ{F^PsyLgAzy7t$dv@qzv&JAxM4Ci==r~GDLDa%Pj-(twDMYVu zkv@>Gk5IaKt~Ye9Za|RFM@=c0iKk_TuZay_r=Zu<=vpw5rut-P&F&f7j~mHx&^+f3 zX6-mpcjPvAVstC#E@ZD0uDl_8Z)7saX2Y7L=sDG$7M>y(Pok>$VplOXP6jYnQJQrv z9wx+N&9=M~uy!p%S8At`XREz_!i!eW5MV5l)2S;-U0KwnL~l-7 z*@`2Xt9`;+bf8&%488x((2Ay7X!Fcx&GL{R4vSaM|Ld~qbmYPDtBfyO#VS^Xm9}Bs z@Xhg;z_j$txCcMy)nH)3n2|~Yo$rqqMU@Ql_j&j+T=K#YQYz9FioL^kYUdHWbYfPF zEoMiSzr9I!YZ4WSLK z5>=NO7u`}TnB4oVy<{L=(I^mGJBSdduxKmk`@^1)TGot0O9Fth+_PrRIfF|HLy z%+1V7KW6aMS}8kboqOx}czrbRPk!Yx8-d%3x&>e0>ixNPUU+(tO*D&S;}*yDdoK8UZFG?R-Z~rvzj~wPpq?I3 z=(U!LRJw1BIvY+}erg_#F4L`2Us7xYBVU|H9l0p&Co{5fpR0Rn@IBvJ!p%y%Xo!i< zE>~MkXQU4c=o~s3y z@tg!?tkM4BS>_;ZKXWakk_5t)Vpo^Dd-%j*N;OF7Cc7HcEQ5-Pq0q(xlAUOvnr%OW7DE;d|$g z4;_{&&M&;PG_v4BL(0kP!#ykUPy=EB@|E7p6^>uS_gPR7?iNmkuRJkr!c}tZ`ym_m z-9t<-BD0q!H50<&cB73S-6o`dYQ@@^vJJ_5yy!Z!J30zS#O~zif2ye#N5drg)%T|a z98A%TmC!x#ywo(FltX;k|7f~%KjGSOIgMM$yja6x%k$#f?Q1^TNJs1l+pG1>45hkV=+HH%M2Ys4#0We~U2_&;%P{q(Yh+I>}3O;hgZ zl+y|#KjGk-zwq-Tn)z0`lNS>F43O=$4_KlIzkAVrp?f(`GC@10*X2xiJ+{l~3;5dJJIXEj6Tznt@&@HKN!MDri}eOtE~C$d!HS(xtI#x&uCi@ zs7nlRY_Lp$800ZA<@xy;mVR}zhxqT@W8l@Yk1d)k z!!vYlHV!Crce^9$BBNFUNH&B+AHNy~hx8Uy`+q9H2s}di0(kQUI8Mh+_n}^81%{ah^YsXz9O$@r=GAb+Cd^6 z%dn-)VRld)gJ$#(BJ_`^=O>fRbJ`U?i^)8px5~&9ITu&=&$>p?O&t5`O z>JJf*5MEyJO?>Fh38(GZ1%MBB94GrE4>;XDo&12lUp8q=Hg_TQ70&+yeWfk#p%0NP zX+weit9TZQ5H3bm$su&@41$GtgB6xkMG$DsAhsSazItE7 zy5>0Ru``?SB7R3+H&Nq37~uZtQ#o(v7nWYEOpweHFeKij-@fH`Apmg0A~{^YJ!Azt zt#m5!h=ueda?cvxH|_rAA-LL|J(X_mn78C>Su1NFz&a zohk}A^M7-B6&QpSU6l~jl4PcxG@rd6RTrxxSZg4HTT z945`iMpFx+-~9V`zP!1}EvXah)Wj$i15ycQHWdCY)%j+l?SWV1^_(h5<3ln;%E`@* z=qxi%s=op-h;}79jSG*qt-?=WH8C}QTi?3ctZ6OVKGd< za2v&eR2Sm-e!qXKr2WB)v)?$PT>+3RKWmm`iO^TG?f=7gR)y?HIUUc8J~^kFOLo=} z!tci| zMm4Ee#YuOFXC)sC_Jr0v*Kk7iRcDX3z7c`9{ImrFYN5NUG2$in`1aS8r&iiTh?i)d~v z{~C#unXa3V8r1vsy4g{$Sc>>I`y|92gLb{&F8C5KIvQY^}YJFI2$y`A;Nx{91Bn~#=Da+u8B4asC zN)D5yS-tupk$S-Cpd#v#O*6}Qp(^H|x-kEbLT#B=_@=P(^7X>Yl?ftQ zB(>}%nOrr_y(v}YQ7VE6>vV^ulTl@*!Pj{Z!-5ubS&)q;QF%_Kkkq+*gR#0+U_VBRAA zm(O=39t0JzU*mF$ndq(zPFeH$_p1i&ZrL_b7c+V60|r6T=KOp;>}7p`|94BYDQf0? zt!@a%5%tHyM?xxhfl{GQtVyMdl!pfG0_)=~PMn={gH%~zTN^-S18|4xd~1BU&5+*l z>9IoKDRXs49omiPF*>1a3OMY*3$*z_td0nL*j@b}WWav`dfRlu#C8r2bVP+)4ch@4 z+mK$8fYEn-(py9iIOKx~4K^%4z>u5vCJd4=0%9UqJv!eRs7wmZkWVW1@I=xW_I{G> z{d%)C#`cyz|Di2(*%H(bKT?uiylNeWQj%AOhHVc$D$y&@<;uo-UKvQsGTkrM5afqG zmpsTuH4m?MxG!vUV625wGFunt+V zTi+EUbYtPIyQN+9PN8A2b;uv7@sFQm`eY?g-aAd3NS@GuHdJgLBq!zRq)ztTLZ!x6 zaZ4K`;2z=>&LY#~y=UBl{L~xWT@Ml%muYjX{>6ZVUy~Gz7keOwDBmQ|Cifx#Jv{@oNzyQRCu zU;r^m7~Y42lB~tpX@LPYh!v#W7=1=^q~38)#S95!KwSjM(48|20{<$E`{h3{!#!Rx zvTpYsgwgZ)`+j$VRpIKo4jwr<7O24>3Fo(_pxVAF=qgxE*W@e$pe4^xjEL|G% z7naXCe^np($HnOIai|&#@QHIKv&2ETMbtfc(7M@>%Q(A*)21WzXqhKtYioWuzwwES z|4`PzNV&hV|PR0 z$@)F`9povaHcp#p*hdtDR`-vZzK~*dtLA6?NQmBwhnaDUTFv-J#oQ2TWDUX=ITA;4 zNd5d`zM_#^^(24IZgSMHqPk1ZVcOV+s%`pGZLqJiM@3Pi6@_@TM}-bTP*9jG2=zGA zhq}E57o!mH%R`VX3I+w0AGQN~L+G~;6L!4@uJEj?oUg#=810=XJQ9v@N*OUH%;~sD<1l>=7^{we!vms6CG$l?n= z!Dy!!@e=Ls1pPuL1{=F(9I`0r>|O-+KvmEI9Z0a;KiZH$*T2-4dvHN-3g6MP)5H;o=xD2r!vmH7ln9u`>o=*c0v)NKLdw)taw;gGnCM3AcBs40$}0 zQ*sbkK?r(F!eLt4`MHJMRYe18&UFFGx4=ErrePKE_Yh7JF|CRMtmlO|)@)(S2uU~2 zu~~S*s9wcF6Mlk9dFWK&%6Ek#^J}&~-k90P-`Fy~-HUIUt}E3~Z77(Vc~||>-LpPP zUMu|+K{<^3DtHp|CJk_-&+$&C*83*Q-)c>WHygWdFM?Tr1%^0+&sNso#p$a4`HL&zODrIr3VMQ4~$)a!da=J=L|0M>$Lmj5tS0FIdXxcx8e35)^T!}Hmh+fPFv(zWa!0<(pC-`m-!CnH3$pPJCnhGod>6+R5BG@3gT7$W zV}&EeE3zl@gk9=wpdR^_Sxtck4pTWygyUl(i<9ghI?=xK&@5U;kq;`a&$5RX3P^1< zS%YlfqtS*)O`?wMvzg$x@l1#j=*#o>?Kf#72{vSdl6AEt$*b(6O0PYlH;JXLHgk|_ zdnt-gN<=XuvmO^QMD`lb`!BDy$!wjQx4QQ3pq9`lp6DPXrJ5nRd`oG*c%T662E2N>eF)(kHGVC3X}9Mw{rfl8 zT?O+uCL8r9t4Ll2wRG5`)sWsn>ylZ$)>CcdpXePHqc>+P1^@b70lH}ibS!crE3=xeJuxJvrYGl>O3$V4i7JH_I($`DZ<<5`X7td z8;pk^Iv4A;`eS*B%^wfE<|H;UDYakkwH98L4J?Y5rme_tuGmhu&t~qAwqv+|q;_$Z zaZ?z87lWiI{pEmWrr6oCIqOL+Mth}W7Ma4QE^X2=K{Yz5*_c!WMmf27?JlnY412n5~2(K6N~Vz!SBu5 zpPX_tQs`0&x+=z}*BMVOLFN&kU!ye;HmQTkymC<4O#q|y5Q5lrR%QEk?CmPjoymJK zHvQq4ZYQ0zY-aslmzN!{#l!WX&ItwRZ;zejzHNKtWPmoxaSHZQ z+?ZChdZm=cRI|Z-O3PrPgzZt6AVm0XJw_?dSTsJC2FO7=&^5rY>Keb7Bz$7yd!OAq zUK{C`YbNTXJeYjIgpv&drkM*Gu>#gY1di8$dsLhMT^XpyZa$-1VZ>Wkx8HTM&7g9& zpvteD4!3W5rS%I#%=PVk6Zmy?Bf@XYGGHtIH2G2TGGOcSBeLjh>?;Esu;9t-|0buY zq=?_@0oJRe6gkY{{IGdsOC|zH#&F0wY;tgL*m$4F zw1&nkE-sEQ8Jbf+iIS&5pfdr0kqcaSp~?j67A(uKM|L3QiMI`bKQDX#!IrId{yxcz z>WZ8Qv_Jc{vYf#(lgeyDK~>6KQ=T2$fYv$oy1|PE*SFis z_W@%*KjoOQuC&H_`L;zNzP59+Uo&PE=`P`nfBc^>TkI$8hN8dXEadV|O(KTydB-W; z2fXH_KyS}|koliSie4bd>{7}IQ z_I(?r^%B#CUT08d=+lrXItxc&E`AoCCAxKNAZxij(0WMsAd5wcMa{oCd7m`rrGRdY z^4*6y<z|$1iPEl6| z@Tp|S09TycbGC<#h_xkjXN)Og4gy~ltE?vRz?!0t6C-qwHB-e;wxAh0$6^8b#=a-t z6@7eBzt(#}H-?I^n`wrDw;?AIWX-K-cS7u+U$S&{@u_>a=rmgq0jPGOh-t;%Hk|jj zG?gluNZ=@;X>qf4Nf9_2@RtdQurVnMNb?(2+%U80kiIBwV_ zmuPkYcxH|ZUrE_^p9PIALiSnoNge^{r^e_VU$1749AlGMwF_dhNE@4r~AMNoWgqfRPMJd+ajdRxgaW&d}vkGOb*7%8dHP1-~93tSF591YM5Wr z{K`BLxuCbXsi&G`vI5B0m)W6(EY!bKk~@>-oH?52!T_w8~cM zioqDQS<^(E%@RGSJY#;EVNai?S!TSvBATY&i1ZSm4+64j=DzFocVC*DcPxThtn@1; zeNW)v8~r@27da{LH6(wE2nl*-{@$-F3x!uP%h5TkEdN-=UKovPy6fUDM-)9Rc{zDDxxRE zbX{>-$aE>5@KQ2SXW_*s15tzvA4~XTNmMG zMPiYIRpX?9^ShB)5;HqNSfO|!6#r#{s5@Pzh#ijyhoF>irIXv(xXXa@}b@(TX*VJvjD9S zCFxbGu@8mvg%g;G>@Qd&B)MFHH0xsYms+2tp zvt8E*u#R=9ieRY)p(g@C$Go7A@d*y^SEr`!<6E3Gd5IK!*JermFM z_5Awxub}*I!#PS6WLe|?SgJnx-D|w>H%|Pq>`Y-_LV$H3QYCmkPP=I4`?GmZS_`|$ z6im@^dHYS_>^lI|FX7c_hy?B(fiFW)56JVeBnHv{tBCGH3j&%2QP z%vW177o|I2-HEFJ$@;N5*DchuTCD*H;1=Ps0I!!w8T?@APml8nsRXy5j_IEhAd zaw3y+zqJ@K^<`{V7?o z*5pfx-MbQ*v*Iw=1Jm1E7-<%R?AA(AO4wZs6-ebjOKJ8bT4*`avcJ=y6xsi{MY@=R za2v9hWV!v5RLm#k=amR%X=!qirF?T`pD}q5TKWq0_a$sO`da4ZRvg96VBTo`CuIZ_ z=aRxZyIn|%2>y3^d6|Njdg%Kv`crMW-hFLt2(b%~;ejg4_M5;n1+n#dwY}mGPoD>H z0%{`PayeXV%K&6+zt+f{$%&aC$nQg<>s{uw@>7=1s*W=ghztz{>5`6D$-0RQ1nBw?C+jqLpPR;`-@!qZEOOo}F1KE1v zw9JcNJ%&c~V6nQMG*2_~0S5-`#7$hBV5mSmgpas+$Y;=VNUSJ|sQ`7qP{n*Rh8Yvp z7*B+gCz6<5OU z3waz{+t71tw_b%2vf~d($0A5|x*NOQ9rv)P?)mz{dR17H94+h4A!cK3>IkZub~Zfa z-C0M2z)sV3aw>)7{a}?D=*7lnq+}UV9sevX&6fn~ds|-FNDmyr!eqWQ^-qI8)MWeq zi7*vzobcz76ALubnQtk*;!ah>4z~aKZ-E8dx~Mq##EaULU%N+QT?oX3))A{W>UDQ` zb{2Yn{_tR+Yq$Dx&8uo2mpA@ zTT^qKMi|3SA!fRC{i0nnEG(%b%5R5C>b$M>&y2@{|H1a z)>zU0NyOdELw^W}yoIEsTp*X%C)Xz-C>RXnbGh5Z@E=33w3rwXdUU7=lD=9V7QF-x za)u-D4s3NCipDvuwv@5>eBx!`<8S!IO;A_A(shiCs^@r}JHf)(e5H`rQiCkCbd9pF z-hJ$rJsqL+`6+{pV-tcDM7jLA3554+-3f>~3vXY7f!Fv^-mi%>7cw8ZP)OMRzM;j} z-_)URk%}w_Amp+%o@B~V92X50vJE&LrFzBz8rkg!+MJLIz&(SvB zz-S|T!1SJ(38w5%tr8I?gtuMxgL7C2w3A?&s2$(B<>60cwHD*Q)@-eq$nay6M%4Yw z56ADB#!C4Yx z>x{4+%qoUk>B+rP(XPqQ%xqXD;fSWgJdJ*xlX?PRWLhfKLvr-_;@P5$Q&Ldxzp~r6 zk{!~H98-yoY;0PugWc}L2aP+-IZD_Z4cyIhVB^_J~7 z2tFA?(gWseZu*3F#@KBZTlphkpCu z>is)nJT8X_u65;Yr{}HeA#;l(I}-B_#oJSkNTLYu*ZSSAoadM!c?04$vJ z!xiGNZ<#WTf@}vWKq5*}_LC)qFNn~O-pB$G&KR)X_;K||m3~@Ut1p_Iigzu?@i7xA zt9o`6=5Qv>%b_0Zorc~v-fI8KCM~)`G&v~{(qpt7v~4%r5U=XsYDl9-eCJLj~KE<|39|ce?}3ze)Qq!Vv?aJB)4CFN(+3E z%Di5GlVa5umWZVxg(^w&6rc}%jkWhfgYf5&d!AzptvrjgjJq1#gH$FJW3c zGOVHy-*lOkf0O&4{U+vj&Zuj%6j|K*T15X`TlVjtjthqN4{087CU=PHJ!-tHH3DPB z9QHqM(JanpDv3=kpDfkw-K3Z|a_n5$pHX(O=&kkaddTJcZVJ7pD3uV?hDIc^&J?d4 z41H(bduJhX6ncFaaOng>H^?5#IcIq*R03bKhUJS`jaybFCanohF-Wdh;!rAPKE}&G z_?-9t!^3FHm4&j&2K_QvU2LkaSEENEE^RYrzCNdiX>3!wF-&Uir3^z2jWnwFG<*jf zvt;Ye#VOkNyZd%xqRqYEEb z1DHkfDp(AaZ)`|m`D40c>PPqJ-JT@GYv30VpieD8iVPJghlz2dprVQzw^STCOR_5<3JG2AnT>u|B?bkl-VscxcS{4I_ZY4^ zglDdbd`JbJebe*KM0+urxp;THX2uPuMAuju-q)R){(PjlkHFb zir0ZoT8h559OjhdRNV1&Bpyn2r1;!u9rLhaiAZ#|$jEtN??11?WJ*%jY*PE z$OQj&qxNo!1t7u%ZlFH%NZ(yE&Jw9_bW3ZHd{l+}B#16?7LQ^ZF#N zAVsO_HqEnY3Dz9L)bEc5o2l{BL*rHXG%QVfP0&15T@n&MmZwx!e$@X*qu-9(J!7jT z=6A5BK{(0_^M1VG!1}o}X_*q+Q=F1WQAXk#giXb%ntA`E{^BV2@VUs77Rq2!V^hUK-Hmk z1156n96($UbgkAzJG;Y%@m^QN6{kc-faLZ zBR|wi*6@j3I+0@id@>emeJ^wSwN?1N_f^+m*5S73&RziM$48FGyymHkzF3kmk+-$u zgx*Z1+h>6GBBfc6oR)}ehqJ4~klE)S5P}>>s?WFiO}=s;{w8=9yRni~Ixhn*whiPT zE9SG=B*uYb5FV+HgQ&kTFSJNGk2*7d@;1A z=OlZ?%qQ^ES!6}k&#kC~0Sm)OL4-LNZ0>I$I&qOlaeN^RO>(j%tVoU${~Ktr#!0+W zJ!YVmmUqIzHR`Ij{=n?P%jD&*QKXlc&rVKGdRG;!nd!Rv+%uIYZuz$%#5gZM-`5L^ z9Ol5UluIVZJrzufPP0;9RHovTJl0?;s%jqApj~BpB|HC!4c@f0Ox}O~hnR#EKfw$i zNmgV*xBn^TnSGC^2m)0W21 zvc&Q9f-5xbtMZ9;lzOXXJ^ItiGn<|nP!Yc*?+UdEj8jlZcL`_)X?=20kT0%Wr^6J) z+uj*lw!-p!b#wdL{@eqIIQ`m4%B|Fe&sLjYa}GP9R$Cph$4DD{3ud^oFE4v9flh8N>8Jse zOu;VO-{K^X&|_80QN-Q z%^5!J&yj7Lxm-$zJBb@;n>pqn=|kSCUP_0(4w1X0$N>Y-(h2?YvZAV;k;P@XphRMVY*n`ajHV^kG!EpWeXs#L19rUl3zmnG9 z-mR0bd6+#7UTp!9DHfgZ`&kGBi%BkGW&l-MDU6-!G+`HeD=O}aoAJN+y344xp0#24 z3BigKDnQXtg(8KP;t~o4TBNuaf)puUC=LluTeN}{cX!t$Kq(Y$aSu+BU;zR#p7lTX zxzBT+_rtq>Yt7!@_w3m-*IfG=+IZSn+BK!fdkW#JDYrdkKXaxID0>Qb*WX+R+ubsw zc%ZcA67gX(t^*V_;92^u@wcA;Epnen8$+B%(u2zfe&vSDpL9oub})eJ71ljR9|mNs8nCGP(w zU!<7#Y7&ZigQKw8H9nlqMCla%|Z5fUf+H^%Ba;W|Zn;`&NcNpOGg+iZh~2%|!2vRy%8 zf5S(+V|;R^+0yzImM>|tx@JJ5?evE_0EZ%nXRhXV?&tRnU`NT<{HtUsl7!|}A)4A6 z$$7-5?8a$V8=FEA0xybQ4wr=hC^*s5LfjUeb+91AY?`>pPK%e% zFDgwQeFfG&O;oC8C~5rkmO#7oPe<*uK{M1^)rgPSgSb;$?jLYuOnppq0up|RV_FIF zSx38*h^t%1@Zh6qCOGNvpT>jra9aB^Xbh6gMdS)TKe7gTwCLS|Z6w0M?O*!m*M2ms z-AR?17}&|h&p&*`y|)oqCMAML5l&aM^NvTTh_?KHQ!E2?lfHiR1Tc9c&TA&Cg4kfG zJsETih+D7xMziGq`HzF)cFMs^W*(`E?C}0q&!i_VN)v_EK6I4SNwi&;=CNm*goUY4 z^o<5>&PAx3`ofC)xks`-8YyAVOPQki+!)j5Q)NaL8|WfmGqKkk&;XA>lIAg`@+2yT8i;9A`qxiwVC*fi`|_AfM`>Wf}CH-+NMrU}R&6;hw2k)8#*JJTaJpuLca@klg znUoJEE0P?f;13kJA+Qdf=3v4ZU_aq$Rt7RcvZfY}>AQFfi7zcCpQyFc2%vNE>8G}` z+VYqN)V@$$aQlAabYeJO!4M|K)?n^(trENy9vMSR>Un$=x}=Q#$|x? z#5vea4l&-R?DI;&AhO=IWc^;JrOy4AR?p9Se~$(|W_l~>dFjb{#mLx~P4T7@K)>;0 zVr%Kc5W91=zi*W8+_(p({6N7=y}qN?Dorb>#q5Z>WBB(KFz- z&5HNLf66by!Dr}b5-Ar6Im3a-uw}m%@P~B(j}ukorQFc~ojaR*%5%Y2OB_h6_z7Yd zMezAa%9im19UFxBDM!bhjmknt5u|XXNkwgxnocGGaB7!4v~mv z0{}E&I~sG>`37Qs5z z(69EFT=L6*7D7iJa;N&r$`}=VqxW;I+z7CrpE91pip^EZAb*b7%ONnmal&}JZu3!- zXyWfU3ETNeA3z`-qbv99gKkMSjx@%cWBuD!>R*C3>K)2F#hSPu4AtsuBN5)!awjtn z%I6s7?U&y^-!9*>dpQ&sdpIbiHnsw5{X104G2#cX@-ldmW2+9#*?4B!31hoiKBK06 z(^(7@|2-i^9U8S0Rc0{nsHA|S5IAOTN?A$00%KC#7(!kNYX#&mk(JXO=S%h@E8E(y zt#aCJZQa!rGh8!~W6ql6p-1oR?>>%Ut}v6X3ix>mXef=+iiDTdu{)&67b;nz+w}Fs zj#=a`s|U%S^}M&8+$Ti`4Th_NH&hJU^`FT(>mf96fhJ`h%MFZUXO~2Yvr)rM12f4@ zS1)$k0eJ!ltdmKJrefSFV{wiCxZlDkuV; z#j6sjvLh+p80djEe3+@T|Ag!0r`GP9k-dvLyFt~`N=CLTZEZUD<(xOU7-fgaHnT(3 zE=upf-+uli>9yL*lI@rFeb0zn^9O`WOi(b6j3LbvnlH&)|4;pI)JG{MO6d^Nz&+%X zU)7q&f?tUP1(I;P>s|m(0P$Ki7yF&)ETqE4?$>{s@sIC=)wKo_kB{jdK76EWrRJDK zq0_(6xvj(K6hXVrQ3%y%e_5i@uac^oI_ruB$chUYR#E0NjA|tDT|Qtoc;S>3&k(6; zC<;u9B2fWG27e`e`EuR=Z|*_=qlkKF-J6eB?rRm^A+xj8sGBxsS@S#MdY5k3oa0oj zIU-;_=Q9t(gT|L9$>Q_x&V|LG?}kaWMnV)K@8UnL z_IMs=$eF#GY>fE0y-lU3^F+7Kb09|u^97TXzTRu>t8VOG!XeSi@&0A6fW|1L=AIh- z#);ndbUMyIJo0p6i?t6#+-2~|^b{sa*_-jI(x70^$>`B!77@e)a{(N{$KLw3)yHJJ zy(@`T)^&^%m~E9-VzI#MV#=%Y6`$;hFXjM+`}bQNFbmo4YN`-lV3jo$Bn&BX;4y21J8G#s5Qw;h$i zo@Z@KzPVLvlbc<@Cj58y*|G4T**|Q3JwHBv&BbSi)=IIi^hOZ1g)`Y&PvT75V{2}MFRx}L^V}IET zttOq$L94Y3b{lcV2h~eZG;s^u7k+&JT1_H-`cIl5@@tjaJ31>|rf&fa1QxhA26Ja} zPbf+5CWPan@8Y6$fW&LEz`)BRve!EKM!Bb0!h9#GgQOI;LRzWhV50P-RPPNzQNDO~ z6-s6CeJnh2G|iVqKq*W@$%>*ELAEp$+kCSHobwj^mj5Y*OPESsXPDbLH%&j`dR7{- zOJ^`|u#{oaW56$%fIRrTJzo4P$(R%_M>@%77C`o*^d3uV^vJaut?c|Q=fV8^a=(c+ zk)!cIhgs^{txbf%<#CXz-L6%6**6wHPtLR3AMSCn*Z$6qK>=*d6)+?C!TpDXoRn>CvD_G-48J~_Lxc`eWV9^(B#!<4u9moAFs zmD;6lS2=SA>z$iTi3;4({-r0vL&~(PpkOIA5zmdY{`+iM!lQDRWqZz!N^bM7LzZ0{ z)6Gp3U$`CP@9;fhrDDFyiQ+yh&C(d{Y0I&2d?VBI@rG)Gy2{l>3e)!k-;a+5A0^Qs zFS%!-P~q9_V7;in8yC_uV2tQW`>=n5QhzUvQt0mdl**;yzPLzrj7QBCY^Q1HFfz5Q4dI81keJZL* z&*O&k39I|{sBT83SS9gw)JHCHA zh<^=&^O3%0hgov(L}$H#aSj86?o7@nh(Sg=ka)s<2onQ@Nfdl26_GXkYvl3aIK^Fo zVD>B{EO4Ir=MbS>bgIm891vByTp;jG=OO#=&j17E6(`5_r+`(Sh+M7a+qr?KVgdI< z!B|SD{|4W>*ffl;^*2%wa(Pi*&|3J?2eZIaa%-6F_E-I>#|9vD9`riKypR53O6fIC z*xiMRZ-1X>vtDoaVleVd!^-rQ$MZXbBq9b3$qyH8lPUcOc;nw#tVpk2=n*#-&HGn1bU5tv=NdT9pN6Vu(uP zyXE9Y{+7ae=XJxc+ZN~S21)uvEqq1wQRU z|GmM0)kI3svOIB3imF*LpajeH%Z<-zG)1YN4)_%12>p#K%qd}z4yE7F@r{dpsFm_G zVt&eFc1|dK?Nnp~vFSclTvVmvV;~9CxognMNaL!-Ma-+r05g=I#X&@mvue;KUTQCO zbw3WJKGt}knIW)|f2~SZOn+`}zTmnvyxDEBV9jxf*!u*&WK&wPa7U!`BqQpx0+nJ5 zBmF(2YVu%?*s!_Br&xA*Gfc@v$X4&dB#eH6&RTR)yesM9xkKrO_I3zNnSH2&l87ZRtynUfNP1~sJ ziB~7b{aO&pYjfmF;6bbTRFwsv0lVKC<-mshtN?S`{!tTSCHJW22Mtei{_x8(Qrf>83Qc#p z*~oEx3p4I9FhrGJ)(1V!_4n-hPCqOy^j9J}t*u5*K;NBoMo-(0QMx-HAm}$Wuzm2Y z04RNM4`9Y`Q#v)$FFAv;q|uYrv-pLZ zPun-P!hw@3t%r~6hZQZ$Z~OSvkz_?ZXfG1m?Feq`y^D(xbAvJRR1%4dJ!wzs$VjDptEX_XhtE#zUh=Q?Rou(g%yN#NP* z*xH*HJ!=U++obmD9Di-=nZ2$csV5;Gb=3HmT}coFjGLR8zv+qcre-Fj{QuN-unN6J zRb%=R{KfxrX}*UL4rX#I{FKeKlzOpz1d)3<8FQ&8=I_mz}xrI`zHV17Za<`Suc3v_3b@~L0@Y|t6u{}|2swVRM7HQNa(|e zcAfIG)6*BP+$;eh-m<(mpREB5vbMK%?kT+-5|cYVR1O(!J^rO_3HmToHqEBAzL&u@ zt84hMG0>M&C6LXw8`Bik<><_ z3DBA^_4HZ){p4jngG8h5vhzxHRHD%`^}-eNYpGtcx1aPlLJ764PvD!+$FC~C>hVwR z`uI*$D>#4QG~5`VTKeL_8;KmTo1RLMjD7+8U*7-vrLIPM!1eG^=DkQ2TkmEP0SB0p z7zjl?>Ts~MLA}kmymUAi4i_38t4HX!IxH>JKdGPE&&n!vur9EE8uI2TuMa)t)!154 z#5(h>Xhq8YXI8Q0uAkr z_6d5X8(X+6F9gBPXmaSic6nPFp;ca7@}Luqhi!GBk7Y-(R~fYn-)UjtR_vHSbGH!_st2FOp>r7l^SC3r;$k385z zYReafnQ(2VF}roTWAQKFWwM~^v{_5I3`}Q{hoJ0NTbr9U(A@^pYZ+)KaK`V3s><(38Y-Hk!Fe?yFbe#Qaxy6vJ2ZDdxK9-=uA~OS+z5TR2OAp7`2-D zsLrevqL>0HX=Lj@WNBej6u!GHB9h7E%cD`RPBcd<-Jkj)lle4sW8Yh6FY%()RQQ$y zJP==+{jJVe>{aa5V%LYsUa_l}+FY4T!OLIv@|ngbIqAd3ot!(%)&v^`1kjESh1|LA zs#LM3Piy0Ric+)F+10a&hb|nPKnmwn3Qm<+{sa1xIANh3Xm9A3cFw@erTGgFr zg(rnj@@zv}he=VHEPfp~I~(JK6s(PNzwB+&OK61*m%@YB?`HqDib)xtn9yvvn5KlK z90(T*8e7Ia1EMc7k#{=_&<8KB5UXLEd^RXb0a8jK-9GrQwgx@@+XAsWqVffyH=J{4 z4yNn!CF)jRPzKcQ8)b8IB)6G`OXWcYvbaqhYbO&Ss=+*7*O^hyK%}{Alhn z(=Dt2BxPM`U0arF;cfv-G5ud1`uf| z%2kL~sb1z(x7h5V;1J~yeKlRdGLZ*+Bb|LQR6Gv7biP!^AAv86w~=IbGNFVmcHlZc z9WyBTF?gWYdAh3Lv~lC-r`E+K5CtfgbJE4Qb*|C33X@N3Z!WNWRx&T<;Q8p;F9w64 zLqLgHXXswAr@FJG{m5DX7MBv8Z6#(Y|Y229cFX-?tx^n%ElPkNx}@N)&XmqMr}UMDiHxf!$Zi_sTB9(NZDyn7%X3;X=}BRsi580?YV3@0Tw{6Qt@vB z!WZZ_WW#SOoOcY1}* z?3T!t1s@xHY3cTR>{Q&-G6i*HeztYCRyx%_MH%kwX}?m_Tu04owa2en{wf|jOI8(` zOI8zLW4Lixmdm%=-RcRU{d<`?LXqFZ)9c^O&k^C@%Z98&MM7@wcW0yrohBky<^kvSKa!bXVXI&*xxu4X+oOE|3iYRn8(O7pJ$O!XG zDGlu~nxzH7=fgE}aJ-~nkc;BRir4cjFM@=mVhvrZ($kYNOQO+!Yvpf!9g0gr#JU&- zH)_s@b7~kvv0A=Y6(j2`s5}feHaW*lprwxoPh6A-jit|u%Ng8g#6|e3+vy|A=~88? ziJ;{A$~}kW37bVZsfBAH+*kU8Ymi@?>|O?0!=8|u;rq>Rc_xp9mro8oM1lrZ~YZK;Fx(D&`O+uYKUx|o>PTQV_H zXM|~>jD1E!8L&A9Wo141ag?1Y3qBh)Q8R9TXQO7Wj2YyOy}}(s*Zvk9;_2k!wPzVf zDu4U#Xy2Ua!`6R)`2I6!c~HU_@BG#SOw&jw-6MFxYBu~PqJ!h3=fer%*ih`V#yj2$ z9{=LEdl3?V5-H*FFp@ZXL%(Dr9y@o#@PQMW(5FV>L!z)WeMfsQKgzjkmY%CH+1Y&v zDPkug{vN)rM()!AT+TuWTjL@@WGpZ(^!*U%scP4Uw0Am#J)RtZCSDV7!<=j4YcB== zx_oAckPj6o4@hpMe^Dth>LGpeCvi|>q%ZDMi}T8B9UuBT4u(#gPp64yNxi1q8eCC! zzvzG5<>Wo7u- zRb*%TXBc@4E>OMoOdG$z<~z1IwSRZeSp@Ex_m%wD7s;#Qsy2RQ9sHI+8QR>O0@{Oi z24=vBUNJ!W(5X0z7Der|Y!dMB#te3Aw0N=d^u7Dr+lhZ^3fwF{8=n5etMf-dPXDBg zRkmwvPj!3#uzFrQyU+>V-DeV)@(z%GVeM0i4jjLj{d3Yaxb`-{hL<8e)W^um*e|P8 zL4AiNtdnMYa}o1i`Lcw4!K+9T;4+g~KUEEMK~BjF^7;ngU1o%;D}+=TtyagV+Y{2W zeR_H6sO3C}f{6~ID0-2OjFHUt91c{K!F-W5Gcz{nSiD{vb=Ls+Sq}*YOw`fQxS_h+#Ojij1lI}v{u`4iQJfbn9jZMid2zIs;` zF9y;(49&k+XEJZjhYs$(|M})XHf_xysSK!V_|*{Q`vS>G$Ny-dlZW?cw-I@88J?|< z+>(UfbEPF?ARRfCn&#*8#azud~m)9K;CC~oT6%L z)Iz-)fiDNz)PHGm4!1~ALzbY`7F{}Tp-{C|BKR&fh2veyVG+u6%P(oZ{&vzij~bf~ zz%MPpwRzeLOm?DuDVU|X1qSg$K82&oKci6vTu^iKD}!5YS`*avW;an2*NTL%qk#`U zvg>qNG2TRR)x$5wA^zQTgxyB9%l%zGD8#!ynh^dkJ(8ZC-gvW#Y*NSE7E?APhbL{&&`O3?tAmifY6h7N=U7~PG&TYojt%)Y)ch!jM4@)04%z9qV#6=2%qWmb z{d--qY&NfDU3MaxrtV2rMh2_Sg23;WqUy|_(13vy5vV47>wq}AJ&+_h&O~0$ei@hs z^Ygp6a~U?FlS7dZYCiKS--vR-+JRmUvn_v@8Mo2U;?b^a?Ngb8g+v?NbD@AcdO-O@q^w@5(xV8)l&3SKmb+ za*``gTC>SV6$?|32i=eoPygSQxe+yYRC!k&&B7Q6L?8ZTHfL^-!fX^IZ9H z;vWexBvqa+S}Ld`4-4Dh`f3k&_4?RivJ_qUs2>1=oP}3(mX4tlo)7FzTQfl4*l-1G zeXKc5qM7ot*)USE!dDpHfgA}q46uBaPcfolg~wYMyOQ}`isTb$XO7cSBC%Abf}8me zAbR!;N-i9wNwo{%cHsJjqT#`b%e z)|(~|2`2@g#mJ;L#WM1BsH1m5bEJOEUA5(xe71dkNACz8mmV-bVs9IEjc^x2kzg6L zQV1|+Ap>2a0nNZ}o(RJuWm2ceOoYJ6U$Qm7LMigoT%t@Nsv1dZCP(eLZ;j*NXt1_m z`EHnBJMcwqfyzd@YjkbHuyS=rq)5C=^*w!d|f%3=YcyJN4Jl z+PAXMNxDehK<(4+xiO-N7DganG`5z9If4_M&ObF&NESjhhp3!+k-KAZpZ8K30>;&#S$guTZ%cIx_v}mUddwF(r3)GarLBsgq0+`$51sw-mv!p25^ht%r~NQHn0c7L&}+o$ z5xbN8j1gPs`cEi9Cr9Wg?^Oe}u%ib^QDNG5q`GY%&p!BGD0g%?Tf@t%tV?KFW8xOE zMzHW?IK8ABr(_+A5d%oBn%Rszrg;HBt4H3Q@~&{TZF}8rX0*G}QjalF*VfYNJv-zS zWp^Axyf2u#ynqs=A12sMTkJe15I3>&^TXPo{k7#&j(ni-%c%J zPafXi+zbe+Y8*?2lxt{YTE-SMD&(+_R}SFM<|ZW#nvLGn*lcTt4JwC=6&ATao1)U2 zprMOoRG_|W>=MBgs|ie2%u(*^^_?TmzGhbVbeAOcQPDO_NOm9lnKK_`ejxmcR$(d} z;eG`s{Ej?HhhRPN8_;0k;Ee$%GegXLXRy;9WM_~h+((FXh=b`YpIE2qX)P~Cr;PpF zG{U1Ve~A=x(wBsU##qd6F*vnb)0?k&RtPdMihkPgEb&!Vt?(I3Q6R2rwgtIKX~n8D zF6kT04c9$+?q-5esBm4QYZXjbO9Z@aZ!mf?77le?j!nxl?Y zw0r|KJs^0}&E8>4>0x{$wgi98l~#q2Dcel(02Dl{8sf(7q0?MT;X60u8$5mBgc9BT z)mZyyx%igHpZvKwe|$7BYCEB#9$L11f6~FytgSrlPy1Xncdz=V(>{hWSUaX4+u2Fp zYLRx^k4C)m`p<&xe;00lH$&B&0DN%lIC`lee|wL;_P zof$b0u51x2=@m?)NEC#e3)fwRrK<8lzhwHxFAn_l!3SO*ri^Vq>Z^HHZ>no+L+ael+qppaSqlwoGtm`{0qAeIl{gy<^!=G%3QVj*FRC}EoQ)5dHC=On z^r`YaJ+$I&inI-#V^?{M33H|Br&!OI5Lav=4!?7l_l#Sp_%T(iQ;IDcPZ9j_v{LMxxY+}=I^`}q5;m0pC8QKG zI4o1pEt+Tp&dO8|5Mt?0W1}26( zIEX&OMsT3yeymsze^re=_wDP$^pJWkR*votWPmgO11u@E`3DOEy!APIEhADBX>;vc zl(4YG4}ir45+Izzv3zxg(vkDlo(BB#fK&nlCsLeizr?h&pS2QuWH{2_+>BT3M0M+B zZl)Cp@rAG4ExoIIBf7CZ_w#-RDF$b za`*eEXQj?ZF=;H`n>kJIT)3E}Q>Tnm#_)5;fve;-ZDKoE8+~>(+i>Yo#IGq$?JyQ6 zE4Zz8xx&UW9~QD^Sq@nC-1^SaE?tGvk-l2I{c+`F_2N~)1(m5BF7Jz7UNWE4(AUqh zmuF1i0+!NXC=!vxYAm6=q9y#7eR64|MN|+I>J6rAv1J?Cy4wi63XoWvQJ{%Xy~2<> z8Q6rLI>z~G1Y#6iO5i~JTeb#s-krUL$OaFbJv~`LhRKzO>d|Rcx%X+#+=HDJ-G{Kg zpXZ%?R!93IRaQqZGn1CDUA1$6vYLwhp0kw<+B|PlZIOninW?Z#YK8YM3q9<<9mn@`%Mh^+ZZgk6a|G|Uf@Tk;RrJJG`so|QM-%$ z`tJCm=l@PrnX(}~!yp9+LVv5TZwgS=yrKPNkbvU?_H7*vK$@AFnQ%;7G+Sz0eSM2R zE{Mz6@KL6OEHEBVP4#PYJY&y8WmV~2KRqqO3(!+wI1q&rqMd-^V=n#inMiDNF_^4P zR>Dtb6J|qfU#C+1Q7y<@{6^)bb{K1HMB<@&nvW3FiQB+j`3#2Vp8>Ktb8+dC zW0~{Qt7dGCj^@LIXjHciW#+bNDQ57jF8<@uOVig0SDu%-x#;sr2!`sKxVcsi&iV75 z(h;vZcH$DwI0eo-vLPWwkP|h9Bn9%Hlpbocc64ON+#uBdR27eet+qKm&d(V}ZgA3f z^RxJU2(TjwHy#Y86pi&+^00Mm_yWxVZ`Mv;Z;qb~Dc8?Jf>IIZKZ_<1bq1_M-0bXM zR=p)ACQaRA#-y3(P}hl~yhI&-gtVLDeA(vJN%xt@eP!dTtC{DWq%shoE{vJ8ePD%ZH_2!JiK=rez3+rn0G1>vlt8S0L#MhB73{`$|6+B1r>th^4+r4&wY z?h#jr@9;9+7hV4tjShw%F)TncDu6+06$I?dv3)-&9?WNdH>Q6qrpw`I{v|rVYc1%| z2-}5PuG#5*RTxtj{?m*#B+2l**JNf$+d$yY1@awigpD?k!cE@Mt?A!iBW3B-Oh zt@i_Fru+ApnXIT*22ZucbQErWNWb|U^xy!z7kU4wDEoa6wNL%QlQ(|i+0LWnpY8@> z8mo&YStjBpSEZ50X5U?XurYSJU%eHLIu(_y*m+$Q2kByLNwU5xg@8#xjplLR%YAe@ z`A-7L{jII7*1SSlu#}5XpfhQDs}Yi!&aDmKra{Wf@3CL;_BPmOlv1}ao#n!1XgT0z zwzVFrUv49bdTpI0Z7mZvS2;4q=(p6ynh{U3Wg;Fqx*KI~M)RdT_=cGA+B(>W{Cx>U zw53#`O||FC2y*gbe10;eGQTsW&a6qoHCNV0n}+*xDYpC^HmZgCKm+AxVj-5Uc}$Tl zFl4Ul!tCtZi3Tptxfd0Zd;PmU8@8H(90r_HI)M~CwioieHJ|E|1G*Xas>Gc9L!ikY z#icDo``M*NlJa2<$z^E?IVx z6ri1x*ra0I={`09=7aD;c#%EHp5$XvK-A}v=#l7y>L5QQ;6mre(KmD1yUL7xJ(w<1 z*9Gc=7ZT*7@c!S3js4N#%9$r)^deXCPOmI6MpFsrupT}YLebwsc&vo&kjYx5k5k5& zNZ-M)ICnWq-4&U4|H4d!5BB$|Cn&B{{E0sRtwhz4>J@J(Uj0Dr0ip(7L{Wl(KYH}2 zja#Cgcxp2r3`;^a%qiS0s66Cp-tbCDNbmsMZET(_cK8ePLT7eZ9e)Ph_$pTGx?4Ut z*UU3(0o6kD2U*$Yq69&yO-z=uT-~%#TU-I z=5-Q0pL>s5nGhvvYp27C^5>A#P!om?8=Py3lCXXAoNan4E3=x?WwJ_^(Hpctd z&`}yB>lO&=PJpd-dMLby{o@3CBYQMR0edktIvON@xDRFe#)0x)4@Ya4a}h5JcGmnq z_2GiixWWU{5@c?;fjszMJ5!+!QWX4efla#gl0rG*sdnLZUB$+h7al}12yzH6mRxGN z;~^L#_?y}Tv}r{D+RD&f8)`CVL)F>X$-c9!Q?S!67i>29yruCwbvxdjn zPSSMVrt{}4qa!;I&1hNFk?-X^5<-GN$O(m09oP>8Uoq4_f&8HZYx&%hc`Ai6Sw@uS zZs<0ivh_cIKGxjXkMD=U4m4n-zRhv)B@R(JVL7tw<7_T5n3=+oowqdk4s+w4!p(Ei zaSB{wXTWn|%`e3^E8QuJY=RZ8l-G1$daZ$*@}b1jP;`LYrJEG(6d#@~u~gZVa-r#K z@*;X4%DLp^H;GF83I{H;vAWSWJ=#6@$iN=i%nrdTFm$qx)Hi9@$0SOaxV$4`%$m*a zMu(Z~+FCU5Eequ&0couDd9=f@%ao`m1Zh43R?OiTt?2Nrzhf(HhMhk};FoEfWsZnw zO4BDhX%N%CbB%H}^{rUCFibB9_!^b2icj1>SdCkBv-ttXS!h&1vb^4yrR9#4g+ zDNPE{6QygR`k}Pp4@Cpd0l_Fi80b+HV~qkRr1c|c3WzbG9tYBg2F$#m;howl4AiKj zV0B5RXrE0fKI=c-O~ z6C#<_@NRNIwQU_>2|W*+yL~Bciaxk>1;0WPWFdKWINFN+0)o6(sk?_#_L0Zc8(V{4oTHa}u9c9kI4G{VH`Fh^kZ+71e4+22cw3H`| zNp7Fke*AgkZw<0g<@1OQ&1>X7=7fVj*W085=~_2W&d(#_kp{g^Tj>-Cz-FfFr0}Eg zTb|foO=BH1%{nJ^`+D>Qt4qas;a!)I`m=;kdLjD43sEOKvJrz)sKVoGIk&`*+vesv z184PQ%In%Cru`$R3uK$CSb3)_zn}a`fISJ`6hmiO!q>z@d$Ssvnv$!~Eq7*o zuCLlRzA=JD^)@OlYKU}j(dp)_SI$e0A0ONBn?y(3(Fkko^u;}eFCDLClkaA$R|i== zas{8zlSj%jM4XloQdynB;cwrr48OPVkQakGDbQ008WCuilrV%z=Ut#X@?pP8bF8Rk zEKL4o26+evlj%Gh;{%=Rb+JWOG28ywo2(}0-JG4%h%Xn)GHwPJhy>Y5SC&;B%+_zM zO5GTL)=QVZ2Ar&xp9l&uUy`2Ua+oLu5?I7`RBT;`9)rFtwR&lk9f^pG2Zs*n>yK}5 zq(Hb_@1T$<;l3TkW$shS8n(YNVRC{Yx&(Vc#}E-K7Ai3ivx%f@fL63KPI(LCCh=fgB;hz)+VCfCaxa&_q#c;!As3?Yzj}pXfdc zOHi3H-8#j@(INsin%og)-TVEX^0JEtQBmAdmkxB4$|L^ZH+_|gvY zA(#v+6=W;WS!84p0k~Q*2QHBs_$N19A4Yiz&%EwpF^Tr{*HUCsWYpp0}iN8?zKM|$a|QzO6tDkZyexuUsWvU*p%XqE3* z+^YV2tMdqNoVWSpFnPMwi*39&CMADF#Jixjh==R?p1hPmpPwkEbjph=*CYgV^gY|Q z9~BzXDU-_Iux2q1h|=AfViWbz3;8}buJ~pSHHUXngz~!Zcj?}u0aS5qXu9BrW@iDD z&Si|5!aa7TmFI@%gE`@ELoIEdw{J>@h&HW4FOE~*9Cf7anmc#0KiWD~Av{905=|AF zO)OQ~k-VHDI54N&PNRl5xUiilyj0TfW zFQ&Jk*>DnZZnPRn#yUR?Q9Ei37Ziy_p*_>%z$RbT0-O8U_$Uu`|aXFfpCka_nW*{-Iip z;%>;fb6{wCr2zCk^3E4T`K2yIB3anZq0*S%F-S{&*`3gYzGouIH@{g}K`c-Zm=CFJ z;OW;zo(-f|Ydj7z-u)$6C|AtMna*I2|zTQX6EX$NYf;PUQ024f`1Q z>-NuKXVc)^gEB2|#RiHmy0Ml>n0O`ab((Hr+&6uSKG`~uePDODiO!d~${TApthGAp z+R|8A-J-7F1T0mx;yaqao_ChNpeSB|)mLQi1a9ig?;vZ=jD&Qafp=%DelcWF?$}<& z3UH#>`=0lu+76$Xmle_jHo$!>91RXP%Pfm7r}*e6{b0GS#`zoOL+J%Flhg~)Pv+F*2tfIUJe`yayqcz13?_oUx6yrh+r~5bhB46LnY@rE z&{?;brQI>O&lC7oakhr>k<+W>8_9nHa;fdjimbU&e=E*aNP?mtyBj8~sf70FX)XP+ zlMSu4e-y2zq(x*`12ufTgiVF%3DCWdd=H9k{F@8kSRj1)rXI^ZVP!tA{E1o2$|9jQ zIW$&l?ou!BNC6dehmPqAn_x`hPPvIeYJ1A*Wxf-g7pXRc#q6dgiB<5~JeP417!20_ zTE@osf~KtQz{Jhrz6i!n)auC~u*u#e!`gl6Dz~jLSk_^xwYIj%+hr$M-igWK#(~%$ z*iTA#>5&kZc##|*^Kc4*r&V<5rZF}^T(H=neP+o=f4lZ7n%r0R=HK1)TywMs?9Vt; zwf1JB8yhD9i$4H`o<}|-pqn<*ivit}$E}Qk^NG!`vL*ALRz3mF->`bE#nXNgCvKVy z(GA@XI&;H`Rimd3_p?WoM?n8y+9MzeRHocet8>6c`s@FRw)ms|%QE{f5NeK|&64*1 zJxw-0V<>Uh7a#@T_F!F>;T`--=hn*dx2LQX^;GdmHOQ19e`z6wgDo+&>rta2Rb;6+ zmkzV+O4e(*Nm)N#D)9f%_1!^DtbN-l1dysCy#z%C>56oOC;|#1MS6fx1f=&)Am|ZP znn>?WdT*gakS2tp7<%srgcd^Re&Z?6bKduzZ?2hp^Y3P7_x|nGwyq@QCyA7Zz$6g? z>vT~yLac$pg461fWr#}}&wrHBr)9C{!2nHMW&NS8OQhPm}3itC8-C$7I zBnfbYaTqimYt8s;&eD+~kj=@Vl+tbId6#R?e&r-%ef+XP~HXo8V@z(HOhb1{a2+1Hhwp9EO_bjR? z{->?lv%dST4#e}Wump=hTw4HF!i}>$omJSYyuxpFWjPHkr2rQA&+LN1qvr1!vF;O3 zN1We{O_9Fl-n=@uA|aisr_U6?b>O?3G$cFZXL@jWoYkBmdE#6AA8W^NiwCADfuaO( zs9x%9mk}M>B+q*Cay@3D$@`wiFZVy;KT5z9z~+vQUdjYrJi-}pe$o{dM^*-q3tKnY zj5x>L6YDTAq@=!BVXFc~6~$0-lap(U5e@7#4q3lp_W@2Qv)G&hU2n*V=1b5iD$#tx zm|Jv1Ba=tc zpeaw*AR$^c+xG0v)Aejb{Zn1~x+49It|brU+Jqj6u;LW~v#B4714}dyiwEwRU3rDQ z`*WlfH1wXea;4>6Eg0?A|L(kY)0zCJRK#qHx(d9r1EmpoHTf9x^4grtZ9Xes^=HpM zbB?@Ntp}TERapoPxLW#yrkOx~n}Y*2+~dzr--$g0=G4SYOt>4~EwOBAYZDOPGHUg*cw>GxjtMgBhsi%Q*Gu(iPT1fwf}NT>qF4hv?-MPEIgm;8rf5 zx-tqG%b1_90irI9x;Hzi64^2OK{>560(QokY+eK7C-?A?8+qB6XJ%)q;%>nbWLj{E zkbUt?{kgZF7|oa@>c_$0{n??((HN|Sik+4=@80q-(iw@caYF}I>vK;u4oIp zJFY(fH}9xex@`@tt_&It)TOq*xXslWW{If;oPn^FZL2JUg|qn8Zad5n=g1GGJN?w} z!cXEYXL)yJOIRvN1@*A73VANn#tLZNBQO=nC zxA37T=U-=(H0%s=DH&<>D1va7;j za-!E(_Tx8>hi{{XfzEI0nO_>wao{1jJN2vZgc+%x<#{ua$?Moc`hvvTZmTEr$>)G= zZyox?^V|qMgVcu}Tr3~=9D38^PWHvI!o&i55sL~S!6U9+d_*T|%}rddG#effRol6U z^}h0=%MM92H6I*A430S~AWqMAE|xBqE?x}6h~avm{eyBuYScg2e-J{*A}pNVg@%CY zBX92e2bwKNNzpk`Y*YMu`y8_1T4(G}OHF;6AZ$wa@oR*`xNzvkeYlwAmGBeh#ITJk znY=ozADLl>&H)n&I$39QHDpX631AZdE>Do$&^F`VG;gp0d_rkHRGGhR=JWD1k9dih zje}wtZ5UCs&tTS{Or?^nHL!0q5ubkL+w8OfHM@m;4q5sGStym3nZUowI|m!K6jlTX1y?`3!6tjG`YZ+mDdxpNe$`g=R`3JK4~MI0(~VEZ+P zKARhgRvXXny|J8s03dO5JB8okgVi_^`tLqYQ;Sbto#oSDoE9@p4{nS1UUCWv=yB(QdtX}V%KJvB9Q zsmD*#9{hTf8UXFnFAV}ry=p%x+Gq_bIqBE3saNSa;~RbRiA`y5W700DAZqTv!T)`GOox;45b@X8PrjgOwRAVB}w)(cyuPY!DJUJK?V@^3`wF8 zzvs0C*m^)q2e1G~}#@+r%x~yh%t$F370P&4Zz+&Uep@pm9sX6RMpKhigmV>FYGnW%tMKm!JSP_aNss7l_NcP`hw>#)XOp1>qJ~ zyipEl(K2***KD#BpfNaI>HI@Bb7aWT{E8qTIrV~)SM=U- zI;O8Pjfh~uOblb@hFaw%f;|UWI9lwo@Q2)%3db#P^0jkwL!_x^(b(A7lFyIZMYW!L zx{-&vwBuDS((uHLNY7`8k*{0dc=`~BPfp>hkYx)?PBSU@CAY16G)}m-e4W7uGOOdc z&Q7aK7ji2==kln8sp4`(+Q005{}}z!V=34mE}IvP(}I$usS6HzdXA|5vo3u5pIUCF zeAGY53Kx04%sU-<`Ti|Z!UF49W)VjA85&;jA9ip+6yUoiQ0*<%ICymBq`c}4-AGw% zX=!p%ffn#)J^dFWH1tc-ll($(MI2K2@~RqXy?1qadIiLxNC zuqSL$Jf0c97=B1SwelU%{!F%LvZ<3YF-(>1RN9I#(1)t@TH#GhD>r)FVr+P@8V8(ehf03&ixn|imY40ukp^v z;Vsv%x682#X4`}R}r^? z*l3xCP*zQw~4USo9y{N z%s%4?{^syN?;C2CD$r1`cAEU%>i1Fl&mLW$jIi_tfww(T%~@o5!US0VoQS>cHB4uW zQO}k?PMdCAxV{)^krLckU>LkoQf%Za!fz@&ImZJW^(vjZ8|-S4!Pxn9-bWyEr}9vm z#qPbc6N7J*;au$Efb1v^aM3&~{B4ln8n6*)w~Ink*smQQ6U-$CT9t$>g%0ac3y*wx zwmriiLuw<6^c5H?(g2N=o#)wNi9Bu06R_ zGf?YAO!ET2bqSh-84$TRwy|jMg31u`##LWKYXqzdR#E`Vxe#*E77qqnbkmzq&-z(r z?c{Kk$%8j4!ma&Kdn3ippGV^SA?quN&xiU$wb4coBz^OXv<%tSQpw@bqEt;w*n4-|6ZBst%hnCy;}xoq`pQNu!Qu~wmRx<+9^wKZW9)K^XPu{`F;WIw16i}np(E!{2 zUReoPFz+q(aXkZ68VaS_Poqa#IjRf5a^jpl9tgW7lR~tXCqo;$#XZ88yvDaFxD~a! zerlvg!}e{bA8H`}#JPP}Yp8BC#c6~nlo@wiJmOQwyV7J=w> z{mscflA|q~Wf0f!Dp(@|_7yvZ30HM_1K;(nVz{hXf(Pmi0Y8YH zEqSk&@*^_MGH@lRN$?$1aCZrH=A~<0hrV!rolJqtB0n0NpO@rmwSeAu=Q6bho_{dg zQ3hg<^XydntTA)R027|;r7)4|mTn`dH?vHYh2-s(li}iu$A+2QsM;T_)CKj1B^gUB z_sE0`*DSf3!q=?a3qp!QMm zj3|swHAkW&Rt>bunG4{hDetfErmpCzIpx_H#UqC&8^|u@Is@m%Wi9c|;Af+EvD{7F zLT~i4jW(I-`v(0UQyFrLp@&aF-vBNp^}r+PGTtE|@h3Mv&+&X(UY?bEZOOQ%>@kk(&8OgqRq}SsqP{MyApp|pxjQ&IvR#@lLxVo6t*}Ic*|6bpo`x%#O zp8KimFV_pHh4J;XNhC!jqq2vx8* z<`L>8Il6(#h3`f#45A9^EqF+clcS3(U;TccFVvU$p_(G7SypyRI~J5sNG+iB^THIj zNlPrDqhjhWcr0ejNET=0qw#|V`-OF6FCD{MwCImj`-$EF=D4iH8CD9$_UK^sHVq98 zKlRlV7zvD(BrMq6`zCA4FkKrg{N;PewTK|YJN;ou1@8;(arJ7E8GXH9tI0Lm8%zb1 zTV>x8kc#TqwIWSOMF_3yO3GxkCfG8f)Z5Hy+|eFUp}qtDLS6A!7rtkIN7K@K=QJflYGDh7w z6ce-Qut;%Skg}?EuhbkxTX{O^?@>?Z54bqE8#hvH{&CAtV3;^GX+7Cf$@NC!XrO35 zz~PIroJ^3RDjZ;ZlZsY!^rmBhLV?i_0kyh-^Y4IwHGM?T$qB)=?=}K)bTTzI_nY?q z)3v$^9VpGum^-=nDcu}I1vtCu^K%DE@5#yBlZ#}SKm3i|<%gnw30T|EL9m7hJq@*8 zT3QnAWf~o_RgmT}`{|+)mU%^hsT1}9_XSXswXgsP_~H$8)9T%ZZb5cAg^5VuD?Uvv zAXvOIMOkS=gz_2fEUK>x(H-KWI#tn7$uuunl99_t$CCf+QIa5x@|qR9R>5qer`Sxh zYp(qR_{}WTsQa1-#pjtx9MDcPb7jxlPkgE|*7N>3VV6bMZ%R6`J!Shu3&P1|#z##G%w{2!JqixLR^s9%ixC z_+HY?AHFNyu~T-R>FE82mnH#nZN%B$-X0h#fGg4K)_qRx!>Ns2_?eVsF!X5y;$FfZ zEnhgUt`)`7-Zz5rn(xx=&?O9X>bA#I3`YU{1l{j$}9DnEvcvkIKw=-_(WyoW0-bKMW)UUPV$FB z<)J45>lds4V&DFmTXydgFiA$>Bik}u#B{_oet=i@Uok1*TCleSJ#6u|Rhpc)m&8Ud z$Qfvgk%K|aXy36C^_A4LUT1^2u58W3L&PM$JDx5XPcc=z|0G$g7yO0up(Yg-n5Pg( zlSp0bP#8gdZKbv?!Jg`cH}lAo#ctl!t3c-j`4D9aw%_m=W2paIH_jc*9P+k z*M0bqTCCtmX(qn5;}#?7HwFSm&X&{7>LyCAv&}MAN|Q6h&>Ky#DPeqh(}>>f(AGMR zwr2VP=^T#ljb*|gg*)q88Ef60Zn9n+($eIYMy%Z9UP!|S4cbKJm)i%JEdA%|{BxD& z<#wN~1jkU#J1h~Gl{e-%p>_16DBfGHYZQMYvZHi~&r1gAAL@QY(OBxn=7j_Yh{+m2FC!VhJ=gv*tsIE1-u^;%0)L zZ?({R0tlU|k2(&~4GmIEI{k-VQN1*hIq4OFHi4OUKOXmuj1Bj-?khI!gj zknN#{10s=E*CDq<`wUPq#HzG{bcz~80lcnGGPi1`xVZ{7Mg!TT4qJ&dBMvXlr1rnI zvTF-&=Cd$tLst*FPi7|$Ny~SNb<6^G4b1JK?|Y*U_l|%PlfI>}(Z~$|xHKtrsgj;! zwH{Cbm+13+F~JqtJ3j8i(WJ;n~5^W$J!0Ed|A*Z#bE;CXteeq&DI z_@bAj5%tFEKaa;h<-x&J=yN{Q=71+{nZg>S6jwv#pLu8nDd_JR=I`uu`uQdhwz-UR zNX|&1PNbkDKU$@RcQ!RR*^N!sOOBz1cCTHgxlem)ZI&`?e{NLrp-?2H9j@2d-IO;m zHx;&$DNk;u{enf-76$zR5ZH7!U?jjXk6~G>ma>H}0*D*zw(dxwHyt0Sn^Mt$uQW`G zNWt;1k`8`+6~%uEV+dA(RKlyTA9j`<6|e)U5>BKf|Q)6T)UFaK_-E< zvV%n5!UzF?a0S&edH;UWjzFhUbjpI=>^(Gvfb9k^J&h*&ktjf73L>|CSlRdkr@2l0 ziu&Mz+$TtFUQURc?&UQ_c-|OX_r%(2FX_IxIFJ2Cbj1|;tPLMOB_hi}J2$wbj&{36X*5qR#~K#UX0#(F!lrFqMkMnH&{ zj7%u#E?*vT;9^m=7ofKC%NRn+??}ia=KczudknSwH2`kY6HkVZF@IwIc!(mGeD`Ox z(nWyV=jf#cpBfd@ztZY*hSE!aEAd(sSSe_8%CVWxXCAesJ0qTHcPcc9{<>?D8)H<{ zkol1o8gYBATF}~dLSrr9OW*`!k3V1N4#iE{k+nPQGgxT8*(1t$lV&4?ut}c2l z<}>IbMLHL|LcNut#j9^6xJORMkf608K>ZmU;_X$(bK6&vE!l8%gn`NyBP9MN%3}*% zS4UMZtg64tuc;t_B3ytz8x9qq_TEi?xy>|Z6k<)sLK{LmwJpcQ9jW3}ZrIL_h&Q8n zY<)sCktB?3F?59^Sn;bO7KTbd6hF8>OkQLCOslkR^}Z}6pScz3~OY1-7Wi#k^4PSL=prrFynK% zhs%0xJF?$kU)6&2sLpUvfbJqo3fX{Fbey}?K+%pG;o0MkH;xm+$# z<(%&BOJM6Nh=c?)Gwpn4ADg3rZ~Q3VRyQYqouni2O6nT=4QRYJ{q8r}F`B{hg@xzI zNoi`{PIKXYopP^UVLXz^Z|zoG>%fwj#6(9Hfl;;TBKDRKu1L1n_~VTgBt5X8cGS~F z8WhBdpc!`LMA^MM**SwB+LeCu+#yNp^!c-AxwIn(GgC3cl4@SqK)o(|t?u|6^$rXl zgI@b}GcbV0?SWApT=1zLuGE6Lsc8s$q?Q+-yeY>xBmp;$ZDs{{3pM7jRus;3e0Pwf zB2?Jk_Cg(?>WP=F;Vu9Vz}&tk>1Y&*=O5p6HepFkNb5+p?7GYL1NQE%?3maq(*MuD zn(;W34+Xu2_5GD0x8K<&EAIr|hH9`St(?vOjoqW@l;7fyhOB}YS+Iy{^R*3qyHksm zaH318J~antET_Akvi!C28HP+w8kc5)F!Pd}o|hTnCij@SWT&Qpv5E^u4k;ZMhA@_K zHK8dJpc-aP)az@q@WvjMoy9Q+zvZ3x-dAYv_1^hBRad6h z{%VS`zCbEW`^L7>herlju!A?kX84bd>l#D-d9rn7T@qqK-wtyV5Kr|@f2nTylVecd zngz{n@vnz5n?56L3%zQSB+O_PAPK|v5pZr7On;SjYyO~ct#9zxChcPv5s%6*S6MnoY zu2M;SsvtaUvOc)H^p%py5-6XrafADKJxvKs(C^Vh}@x`jEd;}p#$GETdYiVa@c3K`5cf=v)j`A$BMf?>v_#70^a*cacL8b zfF7O9yY|ujl{?FT1_bUNx35tUl72h~w94-igUjh#k2k>rC^)^`Sw7D^r4%R<_0M5< z_5&vAzBE!|AT5pB>=K8f6?I}M_x-Wb0g1tB53r)vH>X}FmM83w;-mDLtDRQ^B}gS+KOfyQ+T&wW_4Jp#|uvQYTa6(8=UZ(QHma)5lJ`)K&N z&=8+G_S#CK!s{`=3HKiGa9W#R<-uydObUtSZo@IQlp!(5>7v=J@!AZi8>dHJ2G)T- zd2c*|u5I040v5+dQPe~lPR%xK>s13QyDeIb4`s!+l%3hxCnHtB{sP>QOL5MoIS;Z9 z9oL=0Jja#{m*C=9yywd08bQnI84s0jk`7gpW8#$a+~ru2f4B1dS16cAvIV~oM>Uz6 z;2TwEqOlj}TE&$oqPN>lN%!d5d|B3x>VMUgkQG1gz~|_0_U#p}v9D>Y4Q+pIjUjR( z1Bt}9gbv9BsAkji=L31wKg2$M19%p=RC<#eb5SMl)7^wzfb=@<8LVvv7P|Y=uauN| z0&7MN6Z~2X1n4gXsn%Ggy*d@ny4To@G&%{O@Z^RQ?EQv4RxS!;Ug#Db=`>zuP&TfPUaMzcm|U;XlIR)-hAaN_mL zCZ@>I1@;s*P^kY3LuE#j|LM=|891n2c0wkZCCf`#lwC<&b**SvsGth-)#3V#mZNDr zr2f`nv&w^+%;c??fkR^-=|SH9KM zY-zE5xy+E!j$@IydvM(fOKM`dlMgH3H_ZIi3kTVV*t**A6L?8Jq{+~mud+C=iK~Og zy@RT$IeVZ${ehFad|($7!pYe> zA!jIR)rPkrsyr%vV3S7x1w{%kJOB4m{@J<|Owu7M5Rff1Dj>KM%!9)3N!lG~lO(sI zAl$*OllHNd7)8_#%vDcOeiO4>gnf`Ix!_21KL;Ekfhbd4d4zHm;T3b^gH{@S?DCsfR^9W zL4}8PLvw{mdTR1>wbvK`KBiA=LQH_pW{4`Y*r~#&1V(yp#Q1SGp|5Tfr}Q(Ws|BM5 zdg1V%$a~r&^X@u*IEm!VW4gyLS6v*55A2ER%A0>74az1cD)P{h75s+he)B7}noIL_i2pu@{^vu< zU`MD7BsaUq`O#ZN;(Ng#NzA8K20ow9=P_W&lGRv1f)%|p3a zii0V1yzYXSxa&k7D)pr9wpqZ^BqMP4ylOi8GVR>LQJW9YrH$+I%OLB|Cnj*X?W!eo za4=m>fW)NOo`Nt@e6^LVMGb!Qo_<$qtgm$RYf_E1&$9^g*p7~(x@W26FDY6$#bX6D z@l=KcnWEXaV=Wu8p_d#2i!J%%D+U}niIL(;D^vFnA%lX|aA^Ir4p&8W_UB5Tr~Cdm z(MTj8_QTJ{)63L?1l=@^2(?Q?mkQv)ZVWiLm;7(aR0@F@=}z?$LIaO8{b`s{n$eGO z%N%~*biVE}y&Xo2^X)_4HL;$#G1=DHJ>uX}obc}*{2xTQtNyutWI)p|jpP5?+Om$6da-kY zbsz<^)#!L76BF1i@z;i2E>d6{J6doSvB{5?06Gf^k$v5$Vry=GeWn3f3wtj3R!oZa zmYej{z6n~#siz_0CSeX{hHeXkiakqH2)eUz=2R3ZxG5jqn*GJ8JrSdaEc%$TQbF%< zx<38~#yJSEs)%b0)a38qY4aez62+nTh(m$cN7vFC$5d=w>I z`DhcPv=m1u3rpluOG9P$%B$zd9_wuf$NQL;CZWOn!TcR3dCxP>ptYRaZ%zYyNV2VS zwm0TC8GiTO{Eh|mZ~)gjY_3C@0LJtobMUBJMiDqySL5U!T_(IJz zY`*=h2XQfV)8(q`{HAmZ4ik@`$tn|?XmnDD@3)GsthG8G>1||((pk-9fU4n>D<|sS zaKc_MML|=KXCr#w+vlYqEw$eqyqWWZJLkLGdV>N(DyDm``>y+*ndRXBtMjI}$Z-SY zM!CZ9DUKbbql#?2LcFCmBDTjCU(Sbr<4+gqd#sGa1fcP=_vC{6Hbz&YBlLWkHZDO8P9Fj;4dvO=uuJPYH9yX@_L z_7Afm(ae0>PMFgbIbh?mldq8rvFZFOYh zB&&!4Gcak>xeOuuduNRbKra7__4p|08>%kuGZlg$Q^3;M!aKmHre4C15BZgAMCqGDJ}Z2+MI`-0I_ zH$k4kJtHScY;6Z|7p=kTlKnB)oijETw*SbzuR0U_(2mZ&#mEWQ$Y}7E7gQLW(E|G1 zlUz6Xz!KUbY_&bG=}g7t%vdp@4PqWlcFZ5@l*sBXotFqR7B~}HGJ^x|gGXZKz!kw= zFt<#1Xwiyx6tlSdYV!&GH?|CZ?NXSu(z)eUTIKywz;r>I@e(`LI(N;8d_(TK(6>6_ zD{mdi8%OjSwp@}F#_(2eCg;{xl+qUV;cxqNb*IaIjCu~;rkhDwBVR!$1brwSJ2O~< zR^I7bYR`&B&G4mGPRL)=@s{_LM~W=JKtPXAzK(^q${!y0uZd+0oi%s<^%9LLr%3PG z3@*v5#OZ<2oXvmR{sSqu6~H4;Ky>4)>O$-~U74w_XICeVy?ZR-mKx z96souxX&La0J!=j37=T4N@S^kbGra^I&)6wD6t+b$>hZ=G;gC6fBJLZ5~P~H2n0Bl z)w1`E7ib8C*|sa-s?U(9+UmRrqTTT`{a>pjs#}E-?D2z2as6kT?Djt=Q_45}@4V01 zcGT^ZV6@2zagh1(wgKOWF&vrv>Mr(0$Zj%b@H^i2UdVuF6yeQto!*JV`qdJr!`ogw zJZY$@g10+R&Yp{``0cV*2gIg!<-{PM<%42jZP+80T<2=M(B|giTh92Yg7oSeQt&%< zt_M%=n`n8O`g&`?0cX*kxO41zbt%{2X(wsMiuTDd?ZL`v8eY8+>8%R(`gKveJ!jgw z)5g^j>9aNnbwd0`{*dK1qBV$kUc7@qA~*kj?V4zkr-bareDye=ZBq!mnX>dkmnw2- zN%^D!S&zg~j5$H0BFQ}enpgI}J|WSQqVgvcx_O84jwc!b9;i`3gI1g5TRUc0N?Z-= zVD>ugigTeWR<>w?LYsDuf{NK{_pY6JVSv`x>~yQ+b5KuDa{7+U>p_aw?MUqrP=vqc zC^?5NtwpA5ArFn*GHD@ep`eud46>1}Y-(uu9INI{7F<19A7Qrek+p9)olPddB3S}Z zMm4K~CHJo6+XQ??KeQp#OHxPX5dPTrOM))6~*erd(aAy@mE~EC5*X>q9$t< z88@1FQwim|e9ejLnnjf0JL;q9*;&4Zx6oiJ}L0mn$EsFC^2Z0ZMuba_)LEY39Q{- z$(_m)ER*;ii^fyAX&p)=)?Dcuy+nl$k8U>;^jchZUnqg+EmR`rW-05Q|DLJB&p3Za}SMlN!fKh3|KQ8rlIn8LwrK z_q?^!XZ6gHahhY4AV>g(&|{Df^o6bNHV!vRr<)k;=3>UQTH6kev1=k3ZL<>ueaZAe zk$(^vxU#1I=hFJiZViZlj&61^{EoHsACjV=mD}}F!uTt0f2-+NV*Vjh2f;)7Tr4Sx z&u#LD@}i&f+SMEuk?$;g58le^0m*Z5Jjo4vTa9be3e^*3nx_=)zUoJDBtS`}$;Cp( zF&A~x#HS6+4_wTyw)vknnM)7&8B&NOiR25l zcUct%71Gj3o_v7r+TbF1EG$X?P;*s`?rp zxwR>19dDf-1+1t*MW7;U;)pSse|3TXZUvW%^3Bu&WCUg|4AsW#`=YL*tp*r!RJZ`r zrjb!op{FWH?ydh=j^;P>spv8i0#NFNKe%^Ow=#jXJ&@%QzZ#_WE?sYkud}lx=Jqf1 z37X{ywl)aNjjnT5T7GjfX~iq9fga)r`51k)A&I(!svqrw#9N5a0=fm0yyIs??Co&9 zu;J3u(wf?a=tKI$gPly^_ct(`!uYz;1hK{vZr$P{&7;S(^QaP~U;fEg^*ff_@N;^y zq)VDnRDKrj;eOI~j5*KgB2(fTBR*w>p15Q)E@%z9b>EB2(%T9`14y1@bOkMCVd`&%_8!18z$x$wkS1Lus zLq+wuSu&|Ptb**=<2!=O{_x!yTJw1JoSC+B0G{9`D(z23PZ-9T|h`edTf_28o#C>K4x9fPx9ZZ(+ zzIw&|{BH55YW_N1Fw2o~-g}mfx7ji~+KS~^LRisb`CfnaSJQwZJwc1KAPZXx~SxRdwT(`P$riFkJ`5G2o3f5hYE1*1*Vrudvc=pxp$>Mg^Wu8^#sf4 z>7$H@o=uYKGhJRnIT|Q~(Z|SnO%>*s(=yTTUf5t)nLLDU*7120B0A$uYC{vi}+qA zycvr6%?}+lr$c%3tbZ(bzGS;RueA5!bpnBn=zGlWDPlLSD3}OQ4kddFtSWFW9HAy7 zkF_2@6`cvn+{q;;-`!Sgkd>GJj=Ng+@fzGV9$I8t5=(^6vk3ONd65pY2X_w#y#VWM z@Do5KYQbYJ8>#qF$;ivWjVYy|_V|2q~ zlC7BiampExR6R^f_Ne?F9J8;m;v4Ql_2Z)^b=2p^$Z z=s%OKeks@3B|hn!22_Cxx2X9ik$1d-H5i0^Xj(POE?+F!i_AS#B?OGFa#)>WUgzZE zitdwCG%bmzKP3H#pWiw0tMn2kz89-`5Tkq_*#;BeF%Tab%80_Ze@Z^ynSnoZHug0k z+CidfAE2y8d&7={ryc0Iuhlv`PbBmiH(9ocb(MPc<5UOH0~2~O?DyCFT8}NH>fJ~! zwV5ZLQ=b}3w<8Q$U#a4kvY*K}a6)b;T<`Uic2xOURU5G{HXl*_CP3dPq8}+}p1|ATX zE-CU6gb1ZQQtT~bWf{;H;Bg)Wx&00vh1pFWh2|ix;jzq=7dOzkYEjx)xgbge-pobcmywANsfmb*d67lF z+9l&n@`8w4nU^%yZf=f0ai-LRGAfCFY>)(q+99}InDgSB+AXlDr_ajtX~s+K=6)RC zpAuxIG)|YyBBv|(Q0k@ii~Qbd7PyV^mJ4~g^enHb=L<4>%a;70pg-sm91AvW7%O+P zuZ^xn4;p;g_jj~<+T#fqPY}b9{`#vX&oRII6wU)Whv?7FFk=+0^83WBa(X0keY3-f zYnQl3@IX%E0D;4lEJ44HqVGnAE$!D|QFLPd4Gle-hM@XCAw@5T@HKm)>FH*njPA<; zKGoXKPRC30e5Bru6L&8?4l{8BnBQ?IWDK{u*Eji~U0-xwI$%Ew3vC_YQLtSf18Hy)Jw2%- zGC3Ku$!?z|Ivbyy*w`g#pXtnv@e2B7CMX%6#6AxRj{@Y?x6hAn_Ik^4L>+!b)KSz? z)P?d!ow@x(%xVv4u7$1%DR?OJW?MVw|G4xnERGNzTYpCT7;?tN#TCLPIYuSVpjmGO z%}M0EmPt!=!p#pjf@RkWuxc#`B)KZrrL*i^h#>f_;dT|S@U#j=F1NO1m5R1eQS?$X^+uKy2@{l+Wyv%386T zgM0R7?!hgda0`=XFG`AzxjxS614x5|%99h5e5wdi&swR1pFa}0ut|+TyoAIP>Ihl? zV2DBhUdIKq2gizVBCbV%f?5Y4#A~xbTICZ zbN8$gb%oMhiTpBUQ0mZLgid{XySn(imx{{BvuA_XavklT()tX}OT1a}KAF~r zWZ)nP&`0=`&CAvF9MEe6IHgr7ho{HQ4V7%F2vWICd64uk*x_Sn;nM6g};D%=y2=+?jE|!=yz$vV5}Zw!w4h zngB4;7jmX_T3CgbAOn6KTv0pwXV0>}Pz*3JOO%{XjkXEh%2wf} z4`88QD~epHt4LvbvK=07P5tWObY-RM!}<1-n@o>qr)J*&-XCbNYeK>EZ{ECVHmNLY zPb}BK_I;QDnbn>>0r2`bU$lG(oD%}jRKsj#a@7p|Cj;6p=e zGb7Ax3}cuzN-*P?6D2*#O0608!P|WA`Q+>;$LbA=>S;jg$yl)`D4C)*y&^C@vEMU@ zID=dE0IcNXbQH*jSNXW^IT<1JXAr?_LK9qbHYo=Pghs|F57EUyDdEbYP~pQ?=_0h> z@e6i6!{d>fQ7DuU+0|)j6P{!H%x%08%Nqp-iU9EVM|x;xK#>vhy3>H z6!>b-OWB#_wHw@5e?!akw zoE1B?RG2f_QxH)2)8C^8q3qEV)H-*PPa6B(NwRnTen%r9Xz`Q*@#{}N_HRoK>dy~& z)NcX>P!H(-^`V%*b<9?4veh9I)n9|8vvv={=zzz{z!*Dr0hN!^1sVvx(*j#wGO<5) z1G{mc2a}(RGOui3vP3 zl<~FJad~Iw;_Y$_9~KDMc?t{&SNFtqb5atW%emdewYKF&v7R1;^&#yg(qo-TaTIlp zW1dY&e2cp-Nl*4?BU&c2DnP#SsE1L;F4I|6aZ=xm)V>fnIdx@xRH5yEDY5@awLj`5qPRiv$c7^KsLFSv zYqPDh6>rHmvMV5LU`I&_Nr)?{`mG0U6;h;4s?)&kXfVXQxI6UDp>QZYEn>**Z^S#Bj0v``-G?B7%?vEiwE6Vb(yS z%Ic=U<3)a5&l?b$-a)^(aV=+Fd{ZkGhVgyOyV!vTW{E?rB}_yY=cr7)7jApzlOJ=f zaM7aCF4NJ3!ncf&ms4{5VYb|&XdJ^*j1m3l5G%JOvAMN1d6X=uj_ect=lk6!Nsda6 z;dY719lkTWhVyPD@}|<`u5KCA71D_de@Pnyh1V ze9qYatL#d^lD_{xX2x>+NwdRM=y$7?PAzM$c_GxS%rckenTc+du1xV36+yFRYC`3# zOijx!^NtywfO)VyFlSyVLU^E}0xFks{2#QM?fCunf1dZl`vZLC^Lbyd_u=ye-McL2 ztU)Zzq~~PN;*UfGVbAN`&{>~0n>U-c^aTbiDFtqB6=@NEaHYP+aUQ^g6!@*H6cZk6 zz}7usW-|iRdIn2Rj9%I?7yDKGf(tPc73n7Qx3zh5SnjjekdxThXmz*yOcaRyIK06B z@T+>`wf!7;ejJUqeGg9mKl#(UCQcy@u9l@By*#h&maY*Wy^)Pwl{coQMDFnu?)dF@2YFw4a;`+A#D*d52TPubNPE8b3X~yTo91ki z$LCrxRirRmR%E5e^`##*7@vLAp3|dm9z7C zVV?)p6h&8T-pnmC{-t3dCT9Fl3%gO)+LN%UQmtI5c6yK@Tl3wsw)Oo#%fF$z^?!<~ zxDxb9FskQOW%as;Ce7@x!+-Ae_|E`#56jKlsV8!N5_6(9(k!5PFyk}lOEW#zYwr9N z0^cD=y#D@N5Gx{}z;cwq3;%|~WWcM+nFA(Ew~xKM4|I?j1-jM0G21?rNDNMifAa0Q z@x$9TcfWL+593uH(K(sg{au`u1gm3?6-l1^L9f)KYY9T;>sp+Z7W8J`UZE@ zzO|ttn;gq%+ulGvI+|}7umR82*i<*9wW;OD*l@ZD^GPdgV|GF96jrE^BcYV6*|1ZA zD9okEHV=mk5Pcm#%3-Rc#jwYs(3jAuLS22)yYZHBHM9=f%VX&RSUpZ2>4Mj7OWzdPMf z_Np%lCN=FM_G2j58v=c2>Ck@ItVgJ=XG81O<=VZ-EO^Va~j zO3*j}?SMF@O(nRz{#7|GZA>?x%MUMu7ZMJnpAaR=;~^3Q_+<#Yo|9fvVge@@h?FA# z@*d{d(O%bUps8PmvO^WqZ2?dkbaj6gGbT3Hr7F0jxVX7ykUJ);#RsxN*4{r-@uveX`=$$y@Wx z?wMLxT{=Pw!ruJay8@G0RT%2nkLurcviLV&0=n4b_t%>@NDs`swv&QN3~$`<7e1y!d^R(59h%OJ{nB_APcZxJG{fu>23 zCm#le*k34*?_A}ed>r3N#>ZaLM_*7kk5f?zLA{`W>w@w#8&#v2nBs_;r0VkZ(hl#VeGa)vQr%p(#jNW|l#%25~#qfktfTjkc4 zmc}$hj;&6R-qvhJqxjm@Hr*R9h5}m$QqRvy+{d3ap&ffrnQ_Hw^%=icMyY=T;@<)XigKxt;^sq)GpUP2eEVGV_E&#@ZijGlXz0-F*HWv`Ceu&lRChSmJk_Qhp>ezq&X}#G z&}?mkhi4yey3=iXadwPT18vL8A+b5`sTYIotj%<5N1V#1B-!IL0Z#SdM}j&#JR?QV zbSa&w&!YrL_ftC^V$Pl$cy#kpv^jeai zsV8h()80v&FGalGd^augo+OUIPLLSDlL_oRiTgr45@&*srsEk!AyZcwwSDE8q3D(Y z=BQchj$dkg4tMr?NunypfSJc3U_y zW}588O`Wc(qfj|iS=1$^HdkXqOJ5zc5}p@%c?`G&fX3H z;h^u^N?q>W{ch-i%TJOhXZ#!Ooo^QPV7wMQpCCV{j}M>^2k1S-07$E~6?tQ?+D_$| z3Ow=t^r)ItNc&KBPq%AJ7R!DG?egv4S7$MvWd=jTwg(Yg%=|tA0D#v2L-^OQ9eWUHPY2wG4AjOYQ2Y)>*GFV@&dni%+ASw5d@iLt`{UBUY7^lpJ_Y^3%8)N{reB@JU!}JbRtAyJi1`TYLQHrBRxg_(D1X{w{gh3Kk8#G#@jOqhy8&ydLuuI8r%^FqhK+{zkJm$Xn^t(o%Ep;b z5)cYUT|F7{dbj9OtRPQ(sYHK}ty%m*z<{)1`e40mHRCkO=?q!r#?wedNlvqUdWNB? zi|>vvGhK zNIF5_iPyXsK{xi>dIl^lcA4@UQ;-k1$lH|_$Hd2H!^DvZT~DprmmzS_$tPC zlY(V+fQo{x+0hNcj}ZJJS=>gdFNhmt@FFx_zuhD1I~2Dqx?Wf1hG;qTH~Q=O3Qpq0 zPRpoM6R7c;Hbftzy0Xl}SLC~bq?5#!#hBo6NN>;fPlBacEd?nPV+Ov8gJRTnY&-qn z$YELTT`&kJ|W+QbKQr3+&EGP!C(2eq9%gx!&^=UTnTaXA{mgPsw zaCZrVSuPFL4h%5-xCL}60@Q_aAfa1!ilP*^B+FPcu$BG4tB7wr;c`+;KjUPs-N>vQ#tyWMV z>YT&t6mBL)k3=K9tdA}Q_#nu{&}IG_h+vVFUFes<~B|C_?$oVc; zsJy1EBWV~#7sR^3cXDLNMnQZ156}fDDg#8`1jwPGxV$6gYnuwL83&ry8eMZIo7mcz zCH|aV%uGMGmFyO2WSKH_N~xeI$LE`bUdQ{|+WDa}D1z252$c;`COG^RCMtR^OyDMt zRAXeHEHwefs{2nu9G?{ zGwql~ld`D@Hm~-ak!6$_`_Nd{R3_uO&Tdn4LM;5sP>!h}lYj~gY>uaoNXEwW=v(i% z=s~N|)LX(&Pb zO&f8HRb;qEmul6a2J`aha_xn=o*j~ke(q!+hR(nA3o&lyq+50;3V(=&Azz%s^#Y2ic8X-im7TKSIn6tY)>ot`*%XP1B1M^EnbZgt zyqRhM>rzpBggo)XWgQUJyO7#+P=6F;`!zathwpsEy^kf&s;+3UxQAqTI-PAk#+_L^ z+R<*cyOV_IO=;jcgk$FNEiEPYJH;kgIVNU#BlWhYLOxt^+%%431ie#kIKlf>ne>;A6-oJ5M?A8Er?y7Md`uL5G?yTNs3(%$k@h zrxy}Sy!|BSnZ0JB|12w$Kw2!SCo4{ibu;6Z`1qfU{nrjpbuh^}jV4{H&~LQxYNGk! zBDtkr=Mo?QjbOnwfVI>!{5R&l0gJm!O0L2T+GpT;N7b3CdDY1zm(`d1$104Cqvi?lFwBQ zPlAMR0dBArIAYcTjZ2JUK?V3=S)Ev#U=ju*?c&u#vThB~ z02b`SEV4JD8h`qX^(=@)T@i<1K_m$%F?gFA%-gO5eh0^N^+A)1YjWEQwYqHsnpM^Z z_>P!0z(b4A;mHJ<8mow0BIXJx{kTV`*hI2baT&oTEVA3Kafo4v)JAbt#p)l45>0if zmhpb=&TdKfwe7ZDKm29-q3^wu?rS5r!IX74`}VLmOYyQ8Hj95{qX_zXmVg)~NKYwl zEis9wOyCUWV@A?x#B}$$Tw2(f+d>~}cSxG%wuL%X_mSwT2BWI0=<#~$+vXd#4$@$Q zjeF-^60VH;T#H3BY>_RnlTE8$o^jlEC;SI5cO63euVtzLsaO2HcP!<(_(yN3%|5$6 z3ecw|+Zz%mG#^Nx{n$=Q_na$(PeL%atZ#e_2+E4juYYH-lin5N+u{T4t++))t1Yp* z$=J1jC@k6u_lhS5oZTOn9{WM?&H4>t4~)ocqYr~_d8@LtriO-mj*rvZFZD2rj?t^6 z2~+kGPN;F~mU6A&7;Fths%pmnYhbNH_^b-5IozHR?Dl3KihJ~d&i~q01pvo`b2HSS zYr*W_=ZIGTPwJsN*6B)i2Si{vYb)F#bT4KNFwuPI50B3ZT69x&#bw0s zGTXXi9k4S=Gelod!7j%i?mZvQH?+riVd``+b$_WZJ}^%_XM}1G=A$pzblznLn|8$O zJvj9ux>T?EB4lB4s&alEHKFReDdTO z|Bd38n}XUIlp6;6{#>Xm_1_>9NaKb}e7+Wow(2M;!>`>$Z~xJps_$s?rSJ{^F(e@- zAsDLdVxVtNFBB!neGt8nchLw!P?su!w~RlB-3#VFeK;*2_y^qm5RFIIUDjgN)wAtm zJmdN9+b(eY8Dpp9#!p_U^1{1q;U$wg@33hRqOy3Hq4(&r1Twx>L(;8^u?6`xEuTGV zf7<0w1HN~8DQU%!7E2^PYea_?ug|shI{TybQl<5UUNV^d#XFfklyKQI6DDK~gx!{b zp{)9cEk4|MwU7UYWypuRcz-d~$Z_uqNqWsy?0?>!_5FLxa`pRV=xP>JG{4LB%r>oA z+;4Za(r^M;Y$4&G+B<0V)R2G`NjNBPm7-6Wz}4>|6zB9CZ5KlZ5J5_+JmFs4g8p<) z1&*yqQY~I-R^Wye*A{Hsqm+lhrCUJ%>J%mWjR>biyM3(F@{|FrhWFkiEp#W+;mQiF&bWr&YUAI*F} zlGBVx$FWV6b^mngKcbDFCy&$e$tGK7yE*U7Kj~EYt9|;B?gHVt+GNl7J=fnX_~zgy z(>MV5Z19!tH+E0k!J0ATSKD4bf@TK9zFMD>CiKDe0+KjF_?jl$x6|&CFK`Wjz*hFD zDlgNDAt!+f_|iaU-xT;HPzeu-9iAUMTTBQ8aY5Z`h3dVn{vX2O--2bl+w=Hz27_Vn zO~>})qXWU8iq!rE#)Gtst--4j>gs=2Y8!s-eA?j0V;PtJPSC|+=JLlbdvH+9AjY$g z6RN^D`w* zMa{bdqV^v(_-b#*E;?VmEy5OAJxBBXRBUlLMmKt!p!r@3>L)%4g>7-)z8u^e^KTT~ zQy1^Ms`RjC`Z~j}$OYHGdnC*I_|St*WVR8RU2r%eebTVcql|ORM+54Qm&wlT7_I~fz%Nw@V z(t8f=5fKrQzVheATOuN2mLeiM93*y&h={0vB_@c7h={^&SzC(acd5*Yh=}a;ykK)d zM5G8S#dp~yA|fK`|K~%Ph{(Rc?VsqFhkA&Jh$znM&V#@QHrGwu{Csp>9{ahv>xTIF zi)=q;AtoU{{yy%3E*c>|5MP){i232aN0|7+Otzc#4r}~9B+%RZ@B^D08diP*?i%NG z&+48&Y_Uf}L&GfKv4_d6iJLJJdFCTYbn3tcgg}yP+$n0-| z|5w-lnesnKAN~jF=`&~llk`8j{v|cj+ZN$JMEXZxf4APcc-dl)ncn{@-(rv3#LgiR zkuC0(ix=*MI4*2S76#crq+;^>{`yl3^J>Q{jia66R$6;r{q^$I7yXpuzpnrBHR-+f z=RUoexPh&+PlxF|X6M?>%)O64+dkcT_rU3@n}Wgx$c>BV<&4hu9&?TC)!IQ<>6);p z5eh?R(!6n7)k|Yb1Zpy@iz^&BBOWbF{dV^ia$IpDEm@}bRij!d4 zi8;2C0AH|J4wnsl`VW;R*q9kq5VmN+q*?gF*M8skE@0`av-Q&h0(8seEtheEIUF-% zqfv)xF`;1L!fD0vTM5{$A?)3pe;4DQv$-4#%G2`@%wh#kI0I$XL7dXEDjztGNA`sO zzI#6?K?*j8=_ZV=n&gY_@R)_ETXPs%u+oBA7exWn0TcT_dthJgYi+lnX@~CJ|juSUW z6?P^ho{1H1VBrPGMQ`|^W7rR%9?e#YdblXOo)XZ0ia@kjFX9Ft|93;Wnn+t@(xPBe zPhjbkm*!^>7^}JmAX_bMvZyWLxc)PFE;W-;P~+$ev{Dqq_By~RLEP}&)ngTNpHqYN zP%Ck!=l2&AY%{5(<_W zHwpivFhy)=hudlrz%DO6&RcCYQyl3RyUR%(+3bmkQNx%XyR$r6vo*?Hp9v70k_F@$ zR0wK46x`nA(F$}H|Flxs1HIRZ=7EgN3A(@67APUTc{s<+Ie#bVqqDPO(evA94W3h6DaKCaA z4o9yJlw}k**w#A<8R)J4Y5eoa(5t$Y8Ou>R3(PPoFSu=w7YQw3le|yp27}lJAQ)$h zD%`?n?g={$R9pLEy@(nYM~%O=ZHf2sRayRi+KktpUCb}s1L|eP7*<}OKE?e(e*OWi zS}T2c{xVu6Xyxb%Zfh7fcOR%1tQD~T;G(tJr2May&>?2HEI-Pmx?%*$xB2|R6TPCi zM5$W)fi4N7FdW0?h3w`_K=!&gdRbiWtMt&Tb88&b66cIiin}r)i!N{8O`E!vV!_Q) z=W3>tm-d*=UXblgGk#{_%3Qu(<{3o8#%+lr6^{h{3Loe zvb_w^{7n)jWKYl?zCe{hbJ-|onzd2`9+QFWAhJ~F8+RPHwEG@?K$hgV~|FVSsTA+ ziKxfZw?3rm_LIslF0Fj{zCqjIZpjLlWv6vL7G(R^LUEkUAW@cvD$YYSb4(VsEJmPi zU=(K?pWW(usufjL{-)k|;+7sC8;L?MN2=#Nvk=fgj-@W?yhPAuBE^1;_1^S%c3+u?!qmp!WLV`ykIXEk$zodhH0 zbPN*aFTdDqGn%<9#W)0Ph$#tQi>mP(x05Mvg%yDpF27)drZ*C!`XEnc?VFDcKFw=N z{&{fhu8US<;w0<6 ztFtV@?;7s?wT&UK!Jpw$Z*$ETy}qSNE724lZmfzX&?IROQa6B6aZYVcC;65$I;csV zQvr5jo5O!*ahgiET(c~=uY+)L&-><4nzOKxrc1kN&cOD(Y(uiYm5&-|>5knQux_E4 z+Zr1rWCy8D>42RCtYoKN?b)-=ip>@^KcDGZn^5oQmy-5XpUc@QQAPu4QDq5I$gZ1^ zD1V6W2m55e%+W1Yw9`g3As4hY*E^lP3*g?&%2wZc;$!jzEv^x@rbB z$OKSlpfFKn`9Y(X4H;m&D#2R8;7V45_VT9$j9$Vyrd0K~R7pbYwOIXDn}ZO9u5Rc7 z=fYw}`mSgplY78v`*_ecTJ{5Hu$^FD8t<;)pUOI{)#a}1um(KcYwl?ikjGL`B zbGDuAlZ{%z!fK<98SPEJF)6aiZPR2q|2I)SbGcpy{u9k*E(o#OvJ2LOvI}+68qF(S z7Y+j5F=GSxXuredlANA2^*oo^S`Vf4(BAP&de3?e2xC&&lJr)XaWB3$2Q*76j?k}_ z)qz^Qi!+&#GZasNtqvj>;kNfDEpZkusDK6xG^9E%yInGvuG0P}Aj?}B(tz-=it6k- zCm`(sxv=O?-ua=*!K26>^Emy6KsXkP6GE+PZ4XK(Gu7ZBnOV>F#QCbHDCSW zQ#!2M)8EHcwK$I#XR1`)IIkW^+p&;0{z0Ha4xur#+{Huarqm){CpDywnT+F*DRF4t zrJ%Qn-^||y)n1%|GC|g=Ywz-6hqvR_JcXUXyH=4|-rMcR#*FzJ+Z_ZKvi7o?*6CSw z+V5<%1Qhv$DBZ_)VLP1T1AeaT%Fx>ZTFpvrx8;y2{tYy{pnBc{NdOs6Ip@OYmW<7N z1HZ#mF~~O-#eE(Nm(o%sl!wNuj`7AgYdymaZXY3k4xJ3RsSl9N*gNhQ8FC#%#Ly4# z8C}6h({~KKkHf!gYC6Gaj9zGMlBTCi`NZfFpEWeK8{jstJ6vQ*n}U>Jo}rDq2rh}x zcsK4YiW=*6?CkD##0lsz213*guLt`9TM^l#xR|jL@A(9!CT@~QkE_{;BQaVU+{zSropZsMi8*zkOUpEI zf8pA9r>&>vGDNp=@==pH6ZjvQoq36hyeQG>A^(j2BAN82kBCRiW%e+COFBK^&`^)B zqMh!Y5MatBA6pCi7j8EnPtZn{O>lK}QLbXOSJ(&zdDYOQMOWvB2Ir~N6Z7h*wfpEG zd}`>y(4!fdDeB?qvd^X5G7HKp!53nz0msvGw{E<=I^kF|=`NqL73tT8d%l;`4)$Q5U`!;z8pR>Eb=cUV7c?bgA=_w>Ab7q*#Yb`L*@#~- zUB>)@1*mOY-NQevi#>TIGDJAM~+ZldzULOWu!Q#A(k66T6&wHZSRYe59bzc2=6 z`DaU#H#;AgQf-0>#dP+JYq;4hsbQS?3{MhRj@ z!|3nKyOvyk&5^aw;aa-4twZS#9YqrP0O5wt&y6#ZIR2ClqX)ml&0iYXO0QwVyG);QR&>Br3`X7H0JeK6RI>B0N!FOp9YCo?f4d3WV>n zFPy+{1vihiE(GXzi^Gb{X$fmy3_o5BzA#;u*ePxMByX2uL#diB$`>E)S0ngoo4HgF z*U0((@~ur%Sdis(gm2hH82*FP&&h{yNVBS~u99-Y&#dV;$rnz^|e?$I@ zZBz!xUAyRS*u$YxjDzqkd}1iMNlH;O zEj8pGF4bJ8s@>GT?o3TZ^RC`FC%&t>MMp)bO5P9pGc$TX{jQ+_2MJ*GY9F}PKRh^x zcxnw=ol009jVmIU~T;_K*a-NmNmo%>Ed|n7|7x z%U~GIffK&nwugMiJ$m1{0x!%$54!O!!2{p_WZq)gnb;LKxSw7QsmqC2F}mr}5vSUc z3McZe9RD@{4l(F7I`pLksD7$mnQ}t^p9OCFQw%-My&Qcu2!!7OmnVJ+v}fp65C$9 zR)#2H<~hk2UGOms9*Xzt?GmS@b@nE?C_qPwNYs0*Q~l6&N#t7l4$E#(yuGDh)81KhUqRf(V8?xBVwHqC1F^qZiLjSt1=-q%nhhD zxhx!)pgIhwKtjoeMu^CkkL}W8&GOWfEKqky)GK|G*4?4;a(y7x5w~lQ!tbJ(`=YD~ zW$g~atg@wi-Z-vZ-eNxg#~F2uet^EeK}^j=s*T8?20Jc++~`cnJk{Yhvxf-D@LwHm zLK(E0aHOfr(g9{Gjrix*UYj^)Ghnj^?%X@{ft576nKi&UL62CTD@|S)ZOgEhC@b6? z&z)9w>bOuXPqR~%aC#{i^Nq;gpNw>$@xIM`lD1PDWIBEA98k6EKH99n0zMkL{@O33 zSzoElztV>8yZ1D7NMw0-%u8FW=H9O4fF88HpT^xKcQeh?E1{n=swW#!tEn2!H(V31 zrDygx?UGhJOgAxBAf?~4Z6a7@lW7S z`SBw!P3JHYOcOh0W(4cOZY(V=&?>6)VX6{?9wD`{XlQ@{kfhagfp|GrvF1uzePU-% zQ=WU8b$K083kB9V4NPFbN7{G4sL^*(W54LcHxs8LI@Q;kIxoNO9J)fzs#VI;3x%-2 z3Du@l7G@D=8xnG~}OBW(W9AE^}^!Ij7g> z5`WMt{g1(1yQD`q(K&-Vn$--~LU%-a-^%wKTF}pbFzBi3flO16(MSiyj(^?iwYwU^C+HB=}mP+C0TGWdF-=x1Bq zimtV?o8ZhseKN`|_}*y`FVlq6{u79OaN~)5-WBq@q1P)>JFuTu_P60x38zj3f8HD zQEqC+wTC-5+Y+VPilY<`Q9q_7DK{kdCWNh*UFF{zcvu(Fkv>EVCSR{Cwot~&YAbIA z<`Z0=+kzoQf1dUlRw)c0$uKj5;?^WxfFK&~z%0J1J5#kJHn_)PF&XFuacllqx`9~3UFZzYz3sara~Kvcbc`7QKEuZZ^lR^ zIBmXj>e+QPHKp(Q7Cy3zy0J{0YH>+yC~$zjr57Ex-GIDEs5fb7cGF$Q^3VZ_lL*DD z;7ZtFkecQUVr4stOowOzayFaJROgs5p!J{Q*C%J*WGc5S1|%njt}a?KXPYMiYHjQ? z)>CjG&{xyN&6t&7aM%<26(eTRk*S_Cct9~5e}TtB5RJ(>!z+Cnfo zP1-{_C!2+k2qk*4WW9L)xuJy)8k+q2gN+<@r)rzFM1IRsWy2t@Chomku`xoB!I z%T~IVF&|U!u4f86?ai^? z#7$?HDVdpfT=#EQBRfTd-4i3zJ+(@L5`i+K@yIUETx_#li=*xnDMP)_Rq>QfUOlWX zyKq!z$538cuvnnVsw6|jTU_T^rqj^TqSo=E_t}as5uI(N%|CmJZZsgG`)8MB@~KtHGi3qvn|LXFyQJb$UZi5c{mC6T%rdm* zMX)Bkh`x5JWa-o3equUlj(Wl+o1g%5d*+AIyU_p+d6HMM3lHK+%rf4VT# zF%5n15=H5K;!=6GSOm?-Wb+uY>2zxOhod^vzY0P-nV}?itF?**V^#h9_=hcgT ztGTK=;n6Ss!pjYmbY)k?*$75yY9=)PCfA42MeI4Z#N6pE>9#rB8aSR{r~_OG#yeBS z?K2;?cSm;0DfY43tzq;u0&bOEeyxhps?|>hPu?^gM>Kq%0ke}Zve+zt&O7Ki_;W0w zyXuZo?kH5MgmZ)$U55lb zJ}QZQ56ym6)LM4J>~nM3i+G>vwTZ{gH19lX@Z;q&XfiEkSE)N?yi2e?8E3sQYbTI- zE=(_S5bEygx`a4!9trj@9Cl5gQM4odnsXata|*~=mt=u1e5xi2m<$cfIgd>&ZKoHi?E!;0UbZ5Mu zAAYm5lM`3fRcTN+G?ZVQhoO(&@y|}M#^5JNhfp7LVY-T=o!#%cr(Zdl_Zl$=pg+fj zM#~R&0b+z)Cn1BGi<-|pt5H@cf>^tcUfWK_-Xo@|sl|>*!48!-w7y(DnPr97f|9U2 zBL}7BAA6;U@52V0>gfn(UtrI3%!bEYiC8!xk?nmH9JL%j+hZe_YNg$hE^Vtc3%_OL z(p3hB@9I`S_V7LxDuG+$a;&1IjSN*wsUn>-o+?|hqcJ3L#g=k{Lf%8j^AMGI>$n+P zt;H!oAn*cT&j|SEP%J=~?+P$1(IsMch!|!(u*X_3+pna@omn-DQ=b$Co`>w%w3pX? zj2~{+o&_8F&)91Tj;2bTLM6qp$FB%2rcO@mm^;D@2w1h2@0!--#OzhV84TLdbk8nf z>koC|H=Y2nf}?$SXTI90_Sq`lM! z_GRmN&umtAnw+pWUPUT91&K*8RW3YTq+EYA4cx*m2Jwoy4Sm;k(Rz)|aOOgtC*vud z-P0R@cv;lA*zXVOc})u_F7Snvxb|Uqq|p@%Mmw&G$M-~pGam%pPfS2>wmW@}`xzHa zxO81jn|FS6cxTZKO1g7A`Gc(l-A(sr!#mnp#XBeK$rHI)k3NHhH8+OtPWaGkI6P9} zl+H=DV-r0S!#fMFIIFrF)ITy&49WYNM@L+1qzttO_0(~j4Hx-O>i8rB)KGY;FA2$n zt<4g1EV!10@?uh%^Xg&=RLWZqE#7GJWm5*WRwl^*%H zb{9k4q|obVh7zrK&f*wbiSwQYG$PiOTRa^#?ZXyk0#Y*w0zYr(-6*xuP2Fh6s6VONd7n*jROIoWhZYGyq`EH#6H%NhG!7fhu15DX$R zavyffNFEf@xGPunrqa%r$2EUE?=;cv0;rbDGf?E7`vue2X}C5KkX{lFI7j@EINOQV zrKip=N-K@~>eP6&e%?uNlreh9Dl<*HUZ!Ki6+tRHftA2}R!`I%Z=+g3a}_>V^HQ9= zCnrDnMH=DRa0#;>fBXn?Kk&1eOhYuMyxmx>)IXd42^&T^kb-Zagz9#eCa@R0W{xXH zSrhk^R&*bN2AavHwd;8xjlDe-8l~?6x!HXWN0?`qF((FZBCHVi5`IbHbB*CJt0=z) z5`DuX9oHp%Rj{##a$31i6U!{hSW)29xy_r*Mr-fN+H-g3IKdD6{~AYYrtP+s2_!$H z&bj@?CYISZE16~Z7x}w7zh({X%ru3cP+m@!((WdFAB#1c%BpB@)bc~Gd!qBD^2-Dh z_Q8H3G(d0-r($qGa)G3~IV!CtH04H0lHW|#FSuS%bJEhHBbKlI!8hLrk1N;@IkI#d zpxG?S9lKjyXL3ym0M>wshLR=IHoLT=HtQr^!xVW|>Lw1t!$K`}yaQvGVs_q5o#>y% z@{_g;jp;kvx_2`t(`P>6qouT&`(b~58XHDnB4MgxidEzV3 z_OTXeY};?*^njTzFT)%CP1>*ZYd7Cn?GHP`=Gx{}d5E=#d<1&l;Hu4?(v z($Jczg)d_l-5}sqQV{9N#O@vRnZ=6Bo3O18ZtbJmT`R$rnsMIm6NdsI4SKPv_hq+O zAJCiil%TTo`~pA1dIrIe%wPxOR$FBU3=7yc-S3NkQoL%l^QfbkjvSMjWv{N`4zZEe z?4C4P-Khr!A-7)UN_>g+OA57|4Hz@3FbKdmOQ99e)x;a5$6Aess@FRfch-OlL!jZc zmo{^1FS>}<8tompwgvc`uU6>7e_8oYUe5nrQ`RlYwnfzbr{jehV z?xhYu7GcB^`lrcl0%Gvx#5ce<>9Rg0=%e+Lh)r z5%Qx&@1ch+q&}j^-E5Xm2(S>YEG|rPvrUbrg>-u?r)Y; zw1@08vcomHwD)D`DG^FOq+-B|5LK_)=gf{ADdWJLj)%TcuMHJ*>D*QhZOAdRs2SX$ zLf@g7+J!kiVA6bCahM*tURdX0u5sOXKpFCEpY2b1Zv5yxm#$T| zXDn(q7B$;XKOu0Wm5_!E3d%PuPL#_{T$XU-emb3xAFt`gPkGm@d#}CdX&Rb2>+d!b zz*k+FehgtZfcOnW#|On%ESQQAyB$tZLeC=_JDOJVlt> z;;l_X;SBX8eUWCAh>_EA&q(#ibn@+90#r``bf5OdwA%qKC%|dJTKn@=h9xMQ_#{j> zCH=%N`HB+(S(qCVaQJq-y1{+rR6gD{Jsm;F=j+8}gOI9!SMga&*z1Ao}A`d}y+1v)i!87w5THl#?}Y_nr%g~qZw2!+*Y zC&6_3p?}#al0KLpf+r1D&Ya^;s|Zqievg8CFgAA}sN$6&HQW zCsb7d^%QJb<@6~67SWh{puT+6m*4|m{55!-X{iEdhR#~4S2TiX%A}UfV^MPTFE`%% zZN8`IAnJ7%@~gQUOQ@gndnWe0#@r|;)ZrtfNd;RY1*ZVGvg)-TCh+mG_0qCMi_Jt( zC})gQ4d>*;tGwY<-WZ(oT-?l=qljKn{2R2=hAu+P=c2xWftNI+!4H5kUL~5V?v!tyi$ZKS4;YT5u=8D`~3ds)Y!SCwkqJVDDFTmntaSbm?RB zYJ|Lzz4Anl+4Lm@oylbsP$@JuPWch!Ytm;%v>qZ0=mL2a(6vW1%0Fqlc$11G6Om+N zlKkf7qfsZ$SIh75>|EL!TRKH;Op^kh0&!rVGTwdRywl>?Mzi7kN=Yn;Kk6DzhM?c#9*aMSp4|bk)`iWABb;Jj(hWj72VpeN#=KvdW37>YzdwmC-0U%kr?- z)-=mXL4Yl&BzfEz@e#|OFb2_!{Zu}CPtzYR0O+o#3*YpxX)nXrM38DKlTL7dMSfb zNe?jd%4Um$LTV@sC!z8Iv;d|E$N~6<)Q&aJRxrkjcr}6oVI^-;Pw?hd4IB^G_0o)z zV^%!Y+Fzgk91>OkF5+C;8ZQ|&mmKUD(g0ZP?0_7K8NLC@>gefg+GwP11B*bLiJ%_s zXpA)AuwYEQrEJS%_N<0C(B0nL*sD|Dg6YVqNUqj2@l}Y44;y2%z1iz?z4Tc_D?0b` z?C%0pEiIZlmtR;No48L3Y{*6!grO6#BKq8wKNA;rQ>K!5>QUBt~7BByEz`G`MkRH%Fy zLnDF&D}-%8)*yE8vILpG2f&O0_`c3wh;v*$yj3eo-Cfk*|3}i|rS&)=#=DrR05;oEch!(+RVWXp{s*#oXpCtQs zZFC8*t$@5J5Kz(G%nP#IZl(fgC2~6=uXjk{Kd_X5?_gnWl;2wBTmW&iLEk#XQxyTPQ%gMLVuDfc#s>&c?^BVy z7K+t5Rn&1tc=xP@-tIUDaQ8`@%ZBr*7~Y;5|*s7@P; z5!~3*MKotZ+jvb*{H9!P@V56#$4Xfo;y6&(9Mm_rn=LvnAB}3i0JNOAst?E-_6MJY zXbdSK#>E(hDUc&Ch`5^HnzE^ffhNWJu3B|eO?lF1Nn+pbDV$9wRM2yJlb$^D+(vF? z_H62*d1^gA&TJzoy>ncJW^{S*2j)e#j}c2iso}xl+px0$-MyMogwym93G?+L>~EW& zv@+{$yAOs4-y8!-0QJnSUN&=4aZv$C1J8<4^E-CCPZ}5bcU-1Ns!!>k5mt3W&Kk|6 z>YyHnyBT#hPtLxK^D7+!cWPsvU5=BhS^?on1!NS0b`g zai{uYwa^lpQ3S*7PZjWmaMlyB#Qo=HhZOUVfY#kWrD2QSPK2^I&SERu7(zmUV7_3W zdBSq}g=&C@L8EcFv;;u9TC|=HI8^QP!7r?fh-AXl=L}4If=myAT!6ZWI0ND=G9R-C zO=557>PF;L#f5M$$eGX$@gl8Mzse_lX*@v>h-`8;^3T~@H)^Au6PNEgt=%0tTKMpT zbmJAn3)Wd=NW{?Wc=4u7VpK+>Dn&$f%VUqKfFs;O4`%zaFRj(X^D(Fy`kO2J8eWeb;rCQe)nY8 z>J=9iX)N_f4?;e55rHH;OUNe)`OHvKSOzfkS>D7xLtV6RNr)Vt`dxtfHS&*rF&m;$ z=X3#Ca`_^|64BU$AOQ`O?{~wI^)`8yo})KC*j>E>sJV%@Ysh}=hhnF~g&XQZnu3pi z*FK=78I$va%KhQVYWMy7VBn88pf_ZN6O~lQXgSMrZ)iTIdm94$q>A*9RmJ$(Yl@aLlB>5) zHT#=Ge@Aw(=UR$`gl3d~&fl+wobIa=Ti2l5gC4%!entNdM8%1$Ct&s1zq6xq^>wfR zKcU+HO>ai||5pkBS1W<|_XjC!lat#YbeuWc_*=sF{EBaGmJ-QrHiqWT9CIqWgu+2m zfR_W3z0JeZf{S3|z{Iic0`L)@F9`K2?e0ij40W9D-6 ziKKG1@6{F=f8M8`4^uUH{|nRbP580Yr_XWbN(Q#8tn>B{uU$U4d#NV@O+M^bjY~As z)4+&7D&N_yE>437`^DeWgCPy9MdinV%V0>5mKkw$!-vw)5BIg`g}nsE$9oM{SNb@3 zc#9_+3}6?Y&OuG?pxVe|f+F|3RF#62_veC~a#*wIQJ?bB;4&&xaN}vRTYfnEURAoM z3K)4Vv|!8uCe4<&&a-G#(ZbGte@C2n6%^7c-Z&iVLn%wHJ{vl}?g^a=S*8DW1+FDw z<6EmFhR+whFPgRgvbUndcJ$f1$TKYPdpFieu6mKWUN819rO7|Uhx?qqo3`~EcRg&0 z^Gq)@dBJ*N=x`s|z4X0i{VQT}RQvv2s`n|!H1_f1cLX! z_)mta`tiPtR-pDYV4-6eBbW*+r(r7CSaal`umnn)-x}; z!5x=V$sgKu9=5!`u9Bm@K*Nl(*W;nejLJLR)jWv& z+22=X@q13dr`blr7N)~eg$rj=Q8>%IV#lR#M>omWg8x|l{3*dt%g;ELc<_@w$o8^9 zfztPZ!JwxqPaJO!uoGFcrC{gMK1A^k<1Z*gAKfcmB-Zjh_D z>CN|{In|c2PsQBW72XB6?Qg7>j#_{j4YBaDcRc@AmL%DGw+r5+`bUCa)!IGPF!Q2( zXWroV`5P(ReAWXuUpp}J&vSveQkP`!0)lVfJ<~&ks?#;Q2{$V-h3O5iyhmSKyU$Y{moeJ?Y*G`KfK!~+?<-*oskqLrW>TK{8;W@L`qSj zV2mVs@v=3vl+{+1gay-AY|FRAap9>1e*Ja-?n3nPlvn$NKrya%!kdt-%a z6a7mfi_u@RO4H6TX*Fc*?YbfBZnTuNmH)6$TYb$-+JpZ)X=vNVodl zroB}NVCQ`5bv((`Jk@UqwX#9*ZEq>qPcAHwJ#sy#{}HWt3<5^%rgT*O74IkAL0BbW^jDE55HC=|9v+o#!-ASr|9(L65GEFY%kwIaa~k`-|WqKcLG4*a*rza)&yN9G4fA1w3qpKI@(jG zRh$?qo88u%PZaWhc5=^f<@8doL==_$(wn}jdp#8?Go*fh$ek~rCG!3 zwIqj3tkdSV`-^J)adAB#leQv2mbDpw;&^RzL#bB(c>Z-AT7cV)V>h0)8hxDNZMG|@ zX;>)bh?@-BFruFvIzFs4Dkg`n&uqSHBGx2z#qP+yV}qMXxvcq%-=bR+0W0rcLM|<8 zJ`6Z;`S_W;Ukvu1B0kLHCEa!<+Wb)h)m3q~HVMtHZ7KAf{ss#bJ@(1qN%`v|dAsr- zpMLTx{EmHjUr?+SB+!7{%~=s&P)8Dm4J2igYR%gSMi_Zww?A6S`T%kD#bc2<#O$xK+K_k+Pi@xEqse9?(MrR4Z3+cVIog!9b93)6ePP@(u4f&X zu5kF^o&*X#$~bd17^qrq0Xdak!Q@oZR|xm3SwcKvA_iSSAXTBoI}a>b_@g_TN*iy6 z8e`&Ciaux?1uxII9rSE{)E0(FsQgef6nA#|%d-P=JJT*Zg~&gK{9srAz6G3`Ews3- z$GC^I8oT6}%?d7&qesK}Tgi&3BPNtCpuO$SLnr=lShxPh zgU#$lx*!R?^=t3l_#C4fCM(lQCq_2K>dEyF2{OmU?$z5UQMa*ZUU7Wx6+Y zM|Lu|dM&BbUYxTl^gDKzXA!Kvgd-h|Rq<2%n!MU}-Qc(l_jg=TL8q$i#FpR=;7DJ! zO8d_0i@)iOW%keqxUiK=>b8P&cg>#>`A1KFabv)5Av=_Qp5S#V>E#xc6b{S{ai<(Y z&stZQT^b13_-@-@Rq_xyhu0+Nm*uFqwf}J--)OC-xtMt5Ph#)8&2KOTs7m`A+)u4O zlbcvQCG&e_$lX(y5@xOs#^x;!-7f18%F^{z-j{?}05useyC5z@>{P?FQA$#wrPT zAgFBYDe*JPTXEG&J9wP?+~!?A@~W=aKsM_;^{5+wy<@m0!aC?)dy&`~lci5s$^-k~ zYOE`M+4_C!DNxG_m4f5f&b53*jCCBwxnVER?@z3Sq>Ye)r_7VALk)x8X;~gBVcHu_ z@(oH$mX?Pklt}<_iU7>e2>Q0Gk;x-zj^UeyOMO#RfgHM z*xQE9Gtnnozn8pHxAI$w4qwX%5Zg?)xner66*raa^3LgZIXSJ+{KB`fSJ^%$6aM=B z3Qu*1j@InmkGJ@Gu0=JmBchghC``c-5`W#q(cSEYC~_#ILzVsT`MVKyU!sb^v4>CI z+*jOhpmuw}dh1b;T(kDmNQBeQ1Rv>oX|FF6 zS9~}E4#-ZxML$!@P5xT^b0(AV>m=Qgv1p-Fv*3&`c_~<@6s$GcfO?$BF87pIf82lfwxs8! z)^I5+1cKMgG{@-SN`}5T{XZO?2R{^!!@z$nDn(Mn8I_F8kUbm7-kXz-5QoFrM_UxK?$~YsNGtP*+GwvMSapa7i&;NNJ-%<4*%Ktnvi6?grIISIDa>ScmyIxM| zJ8Z?5ACtKBen2gu&h4V&6`z!HAD@qp)bAsG(d}nf%r3P{N-#T?ELO!JlknJh!ORu7?{T!a zDd2jB8O(I&Rk&T}VcjX=;BAP_h)NvheW%F|;rBV+ob^u2YDln;=XFW;b7x&qqj>^n zoU~N78o88k7CevyP@-x(G{uDPDlzU|_pa=A8xoWy(`eufIiW`vPz-;cX>9un+x zy+vtTS}QioV4KM`X^=o^LT&%pg0$V)1s-IcN0EQhIrmJnF)*P%i2|DU;PqMN1kPJS zN~}&cK1pTF+{(*&NHyf?Yg!8%4#hNlVZKGvJ-?b!W)r?cQnH(qm*r z>_N!*>bpk1>ZlWkbD8Qj{9IlA(t7$)*epLr#T&zpKvlsgXMJdE?jLezx-5dH&l*!} zMsvAV$KNO(8hvv6Te&*m?_{jX7TaDS>8PH81 z0FTdCiVcfaMjeaubj9$C!>6fs@2Xh^NXD}Ed0EkWw;G;`D)R6+AI~4G`SOQX8x7P% zlXCcAy)c30r%cXLDp3e;t_RJiZ3^(ZGX7eRTJ>a)cHyn;>ccm=Ps023ZmxFsvuDOm zUP9A{R}HieDPfcWyLLNQb*@n^7oL-^t*BRLqSw`h+9Ri{PF>rv8kvb>L(T?v8xb0| z<91@d{YLlx;lLIOlBP;Unxvz9*q>u;Z<)Ui>)UryA!k~FI+399-2|Gk}!5BwkTNO#q|JO7u{2!mTvC_9P-;kk;Ku!V!1P$AAE%@11bQh&{bLe z5pOm|+b3%KJbK!^u~aycY;pH)cuIjlglzPo2S*5i4UxJn`Ghs_R~z;!*jJS;@thQ3ka` zxk)xycDwNNiGmM6=WisPgiHF5;zK|}?sMEu>eWz-%n*D{gz0Gmsb58+>---j5!*xY zri3%aQiIQO*`5h?WqGy4srE&so@fY7*)}#~w$EX~P{)z`(5o+8aB`+6?<+Dddq!=P zulCF5s15a{yd-_%%d2436XJIZ{vsFG1oY7!fo6H!9#Yyj5ni{OLw~HS{&gwOOque< z{Tnc2<}f;l)32d6%Q$@{H(~e_{laEjW&)fz9VWdFsPtGDT!-t&Fw25($Dnj+Ij8kf z<-v?RYH9rQVbFYd&g%Uj8D*9)5LJq#!DMLv@z}8Pj^F86Y>3eDZ`PanKIgOCj;#+R zO7_2TfW?L8>Zc4^@hcI|JolSFzZ?Kgb6W@H3LK_r&!`(M;XDGQGs@MRWi5Kn2C=w& z{?_rLtTwY$Yx_{-(ET0f*`Dc!qj)j?j%X7nR@TFfvr&E%Zu1+AVbcqj(w1OvfOM#_ zkl7K9D*iEQ4}Hp{kU({|Po;KU{EzBj3|-&%|1*HL3^v}#^s>Qu-wP&(h|dqO)pn>E zp6fgJ)>Ke<@fJNdyY4Xm}zVpr*N2OdXj-yFm`mEf_Hv- zHrVE7B5ce%ZGmh#6ua8-9ge|ehlH&>jjYpIm;M_KGOo*lOJqUsD**a=SU^| z?0LzEdzQJ_LtYjYZx4w@`_793PHq9{XtI zC++-xC@P^(p=IsFOl(8D4*tz)GRObnx0ep~^*#|>j2Ta2Ik$Qn;i_ZpT1t!*QT5<% z{%Ix2T)iV|klcmjDPr>b3T5;#yugP#2q{eUG)cw~wJXv7X1GWR+bXE+gCneW02OOd_sD!lY9`HKL z7!T12+ouL6<_@1_2`){v(E~fLd7v>Eog1gf+KNbutXffbO8wenY+~+6Vc1Wn!$Bu( z52sN~s!vMIPhkXbL)Iy+)=RFC-#dD0{fo;jY%p|)b|MG_p@y1h{ z+402=8E6PnHAHXEe%^kBnooNQSJaO1g=X(noO(@fD8h|pb}+)qRGiu`&Oiz{Ckd7p zV*O{M0bz9XKuPFG*8Jm48UK%l<^HFvUv@{4S3B<61-;&LjF+r#9Z?8;nO7=3^*emY zEF>e^C6NvR6KK7B&j9lw83)k1$nH($$4Oy-g>U3v;8`qR6!^`K`aXTj`dKgL_n*hH zKh|W>_wL+fFiAMD_36Kc>4RiM`)g8Vcx06q*Zm7 z2*!UoVI=Rx{c@1q@wX#`nK1wa9icAJV2gTg|yPm1<#;tLgvZ zyTVqtP5e*)Q3X#o|2+>KO^UqKkXQCXljS9UX1dnLUiQkLoBUF=ky5h~dE`Y4SsL+C zt=SaD{4MxMTtVqew1p}Wq&@I^78x2fqs?AuNqrV2HtSz`mce!N%;BK0DKo)uVu-C& zNzo%_wM;1Zk)j{-8Nn#^UeKPv1?x0+Fi+H;J;k;$S@7wNNx>}I+qR5C3?)Zk>6*Fh z%Ji^`^ZYDzrPs+Z7{-N-63{Hm-Tf^|dHX`l3~xXet7R)6rtYW$%93V+-|f&pHFVVY zv8%t+EL^S9_{pbD7!-{kCWgZDw8B}Z3lHW64~@9#_=48B6hr<>e&i+%6Z1HPpPnp7 zzwhZ%vm97x2mjN!WD|D(ThYb_8(Uo$>CH)vY%(Q9WZA%fXd^ud+2at!%gof=+8A10OR^x2(u(wq7qZL(y zrIh&5TN5UlFsB&U0V^R6^X=#0N1$-C4vld$!cqQEimN(5v&wr2)OQewTFX`6>N>=1G_vtA4S&9G(c-GFJY!;jjY!`CC%E{Vrkn-aKTED){xZkZf zlm+(3-{KkWb*qc88gtmQ7TQfaJ*h*-do5qWe#-rK@7mjNSa2(;{aZM}BrQDy%li#oR z&oNc!z1_S><9BjxDTNjU25vmp{hL0|zF*>!3r$PX8o4XP8&w1_kM>nrfv~y62nDqE zKmENS>Uy$vEYnCk+9#z80Ilb_CNViF zr0C+Uz!!BW{15;f_2_P7f^-|Z#EEXz30l&)SZ)*dhK;};X*K`k%#Nxpfr;c9`3f(5Sw#-< zk`<6=t<%;VF>;_8y_Gg|A*B?OSVfp-X&!~9A&gW@l$!ILTsKA5DPJ{b2)=8aBybWv z(l?T8MP&$UuqWu#0Y2liSR11q&9L!5KwvMeAWaUd5)yMGirbaoJ$8}eNnlBxvR*%a z`DpCvt77tF%%XD+99;f<_2Xs}uPn&(gQTfPt_{N~cq_inMAppW*RhNjrT>W#yarpz z=C?OnUR*!Fl%i1USyL=qjYsA=1DcI<4IS-{PIHuQ9VMJPIx+du!blbZ;H1)MM2jOd zL3jyUHInuNVyMr~tf~vZAb)V0og8})`8ro54YMbyRqiN1OG-6zLJU`0GPjOfcP9!? z<#@sG2bQVL4#%N}vstj=iY`v(7DB^iFah#MU|){UVJ?tl$KGp!=6>YXo$L=0>1H#; zro}(Hx31*`gPkpRXg469Xg>w)~9qTRZDPTgW4~0gPRhsAU6$pZTukTtA1|jTa@bNE!0Vuih`i%fVE)#c{=Zg(e^a zjh@3Nr|Hn>JqK2b3Vw+y?^2+lHOA^tnzk3T?7y>Cg`}66st*EI8KRApRDtz-g~)1{ zrhLam)?Et4?8>!gb?mW*m_IYX%Dq(NXMF6#^`J1#J_9?&UucUL8p7Pdb9YdtH*8_ySEvG^DcQj5oAXt6kbo@Zl>kbmf3IAy>+)7hFo zS{ropkX9cJ28r!wq;GO2l$T}G)< zGJ$D@%u>E4HK-?XEdG?WVVH2Z+X2?M<5D2yP@=&u(aHv_`io%VAn z$#*g+-SR5tD~ZPIXDX5YFw%`eF98l=ju@QWP~cw`ch|(cK`U%#;eY-aO;YMjxcdzC zVLwgVE@-aTNp|;X}*V zM&3H^3Zz%<^Cr`o!*8Sa`-Q|60zLhHyqJtIDd@L}Onx&`d~Th6u71$6AXv&edXUr4 zPROt>q0&tG?JMKqdA8b7<+M5H3jScc=b|9Y6Ely)WuNrrEbnDb`oH%JTi_Z4S8SC7 zf}Kw<{wY~&J%;CUbx-`!%vQopxZNtg;+XOUmAKmRm?kM4N;V&+4~DXA${+3vuvm$b zTHFC4!CV=w`M!(Uj!)aIIPc2o>v&KSrNUjX+*ulxc&SvM+{XJFT91SjEPS!NI>rA2 zUzj^${e8)x^dP?dWfsFlWo`44^ce* zGOn2OYLP9r9~h~cTV8mr+0u9Btb9B~7hii?m0>(QFz;K0BmBjf?l)}2U8lvb9+DjC zOQiiF>+>mzPkJPEUc#B*6Mnfl@%U|_S~^XCGAzL!teS&klqnnB&zX(^1-P%Dr+Ui= zd6)8uESkl>yMW7}NleIT$_j>hT2pfP(sSZ@-+z>EqjOpzS|0Z+QxnZP^^Yv6ee0I1f}n84K|nzm6;Coxl*#OmT>9fRLAn8GCZzWmi-h= zva;nZH^2s#P-Z={(9c5V;D8I7JM}hm_Bp#+IMvc4Kwe4gWx(EVujwD__<=gP1vf*Z zSQ-|3L?YXVOEzuI^Ar@H`v5-3kSMx$GthJ{6kWI&c&YnuzmO{x5k(n@W$0%?7w#wN z0FPdcU#0;;RndL$pFV=G{%9O1p1FR%yLHv^MRc?GmfSNT#&9*QAL1%K!@I{5Xj7}K zAmLIFjncF|N%v$Xsf}IgA{sf(FRJ0$6L|5)A;PX1x--Qyyp`Dz>b_`-nzq{4%P7CE zp3ZhHQVZP6$qh2>PCRQlq&644YEgJMO^-)C>7C)q6P4(zTs2SPZI__V3>CbJhb}@w zo!aucC>5cZ_OGR`b8`<+7-waFwHBq``%Z`FoV+|duFt^@0CkDlclu=f7<5~J|6S-W ziRviI3xkDQZ+}{i^67JOoK+7k;s!gnoC`1Gx$sth&weOv=`#tk_3L5VQgb`hQOr~I z=6|aLsQH&a?zUC$nmqc@F4YRWT}077>wpx~&G0@GCSuatXZzO(FyIu(3Tqv&(Kt&SvWVxX(8GF1b48Lzu&yGsQKrO@B7@^Hr3gUdM4$I z19|hId3Y9(xe%YV{_;b|C#1+UE<0yxhI;S|r^HGDb(D zt}&H3rcUGDO8wF3?jUsdGoNbE8!}p<(V*@DmOA=5KJLbh+HL>NxbuApGKLggd#s`@O6zd!!*CB{=4eN9@849L_C1H6(jeSN zZ}pHFOe zk>r5kDOJaY7W07@Z|<*1MADr`X(?UOUg>MeT2;;1=+0-wJFVA9JGUPq>cOgw?NUAl z8CLB>HggPD$duxhz_1FAmq627?MYN4z0J;+xsYmqeA)he@3mLU_T^Fi`KSD1H~jJ- zO+ec)G|oGFs@*^ItC3sQ0R#^DP-?r^_2Q_K zCu263Lt&Mkg9r9o&`Y_!;OVl*{{p&#b>fH>#FUUa%&OXQ!qBD|1A6$*Q5a@hpuC#A z(Xe_Bj-tr9eRH0k;O#(0Xu7WN=B^``f$bOxJ#?UgXs7qnm;%E0^>#J$l;W9^fHt%F9QNF3}z_&!bU&de%B9?jhxdx7AhQ#>6@&c`f0mqF>$r~YJPf# zt=`_#X1-gPz(Lfirrgl;N(3b^&!uiv042a5r_Z_|zj9yas*!i$1JcpACwW|Q?JeGdr~LkxGJOxh@?BX6(dco<6(KgpZmmGLgYYg6lHZHoE%m-F`%Ci zEL`B*gzr3BRNexf(uEcm!w8{N!9TC0G~0k1LV&e}f`DJPQVNrDO?|V``f5fX_ zNGH=@(lO`gMjLl?xL9DtY*o?Q5hvU&M_28_v$=+%yxTYI#S~}M#gwO)BMf#b^7emA zY|(pmAMv@NTCS_hQnEpZ$*!BGd=(_S^AJ9vG_?Ec`EOx34jIF-L?!E!z}(y3N%*I8 z4pyb-$c5 z{Ax?vr{@2{PJiy*88bVZEn)`G8Z@3gsoYN=>8a59(ePqW=2k?>BR~Tc#5`tKE zV!@2&W97>9jUvgO82EYUn-PU{$6e~8!Z%F#+sqt9n*F63hi=$(uEK#vUezgeq-R)@ zF7?c}9eHNEg@d(icJuNhlGT4{dGHQY2kF4}8?0yj)D;Xh*dpWzbeg80|@ z{F5y5{uE2V+N}S;Y8XrGf~c>k!l9iU(0F+Nf)^9qp zCM(1g;8g3|mV#CpY!#5qlI`X!q5Bz6Z2}aJ0L{!E8vgfcmVcZ$KV4#2YNxgvYae1|_bJk2bWG>nxRN2yVL1 z6#%O4u?~EXTuo^y6Ob0}Y>;jn9eBUroR%obQC{t?;!D1T$FZ4s97up-m-26giG9&Ra%y*g3}7C{8nMa-cSEiL7%llTzF z%#12D3!xWN43;HgE%xDCL5B77{;H!5*N2*wBgCTL3y}ynF zDbDGs{P$Ef)DoVA_^t}+v-?%h4^@+Z3SelLdWicM~Oy3DBG0@U?$O3#Ulz^kULo{*Xc$GztebA_B+Dcr4`R2M}8MxM^64|-9 zlR%b8qtVM|OiLVJxpeDhK~0c)h67B==kv_ttjYOuXv83=wsz49x=C|+7*(z^uf9H~ zdmv{a2T@)Op4{x>WCBJH$yyS+w>refMtDL6r?f6joxMjosjd~Pzxp74_*Pu7LB@nn zY;#^Fh`;~2UHF()bj;hDaLCu^8$FQ2ZvpDl34+ury~>K)Y6K@U`Pbc6OWAp>Ao2@e zRn9Qlz7QJSq$f0;=nH&hM#@S$Mq15m){|u4_218_k9h)X(3O>lvvR3&Zn|if_s~Q1 z3CUXM@ZMs)a-E@Yf$3Q;l&Ak7UdhlVxA8J61%q;7CFiuA5z<6qiJ^E%T-oI%{f%24 zBVoh@JeB}<{&T{NIk6Wxnkc_<2dUnL04;|RJMXB6Z z;{I0H_cI~p7UN-;)5w& z1Ja83Y8XMV4sqRR)W9{-5ty5*nqTaHD1Y^Q%B;;rx`RKFb5j2EdXZD$vts9@AEfjC z%ll7^;-QN@f1i+UvBK{gY8BL=`qpN{8?Q)HRFaG0r+{_IB(=r97OgsjpmHZtu1q3& zzV}N(gPLE1OS_`qgtxlV9|%k(x^K4c@Vpv5GVf8R7P1o@iWVfaIw*L2W|k8Jn{$Hu z%CT7#8Z){^Fz(YPAb%efbuEI>+bIFtyz}YTX2V`OKJMexiMJV8nm_sppgN6 zYJ`^ps8eL(WWTbKRmq??zb%kd2<}0S_`tM~rylQk>r&qY@yQRwC1xR;^C!iK4s;_S z_1i9>_?EUZqp2Rcbv5&qi|9vp zB`fYfdcB6fpZqw1Kf)?qR|{%%gRI)Wn{9g(87KU2LzDJN?347ZfMa%M#AC7UDWm)m zqhJ`_jJ4%cWv*EJCjWk06nYS$cJG(>S=gZP;0ZCUJTG*_(Rc7n+8F@;@Zj%>>ov)-T7uLH2I3JMJ3iq9f#{2r#A2PPX z*qwKX0MAS0rog4Y>JIO*DR37ZGEpMCqlQeqCtW>1SL-^eTdCKrYAm6y3tdvPUW)n33kia6A{UP|S zE4s!-wCiZ%5V4p^d0@$%4c14E`n;F1cj6(*sunAku77b~MMjvv^)2zgQy09^@v3SS z!A_w>2Zy=yXOv!Ua~2_+C;OAXBczE|ONLgeq=#1Zgg+%59#~axx2mC3#Ny>P^}5}o zu%QyLzw46a`90UH#mtJ=@bODdLrbr4m6V>k-FSddw6UpAr0bt@ z7XW(VlF$qYYtUnouNs3gDQ}YAWUAK^2D${2L`s04?y{q+%)VY1dH?;T6bd*v;g)T^ zBJ)eN+ARsJ!@-~P4Vtya-ss@S1QSN-aZ-oFm$%qG5@cD+Cet^$8jXdgYZdcwW(Z~D z)%kl&){U2Xzsz52Ft4MU1Ic5N^RE^eUBJKEvZSz&UqYT24sb}wu7g@!)V6}L#>;{k zJAZ;Jp-*BZ#!vh0&r63K=;o3t6VF|!Xa}b0X)PZ95G={+=EnWV5hc$&FY&cQT&N~z ze{Ml`hpN0B2Z-_h%B+0*#t4RQ|29#&Ab+X+{gz)kF)*Qv{5U2<_9QBSJ$1MbEq3WF zR*?H*`-wxAzzf@z_9kLvpp`*M$>j0~DJ+ZUXTC;E70kN>?vm!~CMmjmmi1u+0Z6Yapp zvu(FgeU~Ce?fErD%!(X=;pw^7# zt~X6KX3U;PMiC%}eZV4VJO`hg-9*AKv)8egB_8=Dvev0?52g4x)ynq)^^>p`LIab_ z?{A7PmU<3+jlP?IBZCUr+{(OAzN6F%Q;0S|Y(riQersn7nfoZNRi34G@s8Q&o;kZd zt+Hc`G_J*7Bs@!N7yKGGf4Qo*Hl_~=$M>b{o;veinPT5iC9SVo>{CEd+{_ctr{G+xm6T;)tyD2N~1?{LDOdwD{c`@6%{FW-I_&aj>#x$ns zdOcY579s3XOPBb@C+>pw=d zKJdtRk_ZuK_TO54=5fQNdRNt@ZkuaUY+XYl-m3No4XEI2RJGI400pV%QjlkB@uxVG z6KK7J(-vumi6XJgb>xvJA~OhK%&`;q&RibV$}Xn9^39SVzV$X%%7dVVyIVVy`q3#l zwKV-1<9^$F-0$pJj^5J;tJ}k#AM%uGb1UbyCJSfdnM1U1w9|>WBmZO%{K3vVLhZ!5EQZCv5 zzy+85DY+06;NXZxmQ}%&5qN{L6{y^~-_p)num?g1)ZxjSU*n|-hWeh?nlRX$|G}Zoch~WPUmOEW{9ps zz7iG3YL=>qG%(#qxLE(_Pv=;F-;K?Vva=%H=SIcu1{XBEJ`wf11w)EmH(wh?5%@^AO(&A#!kw3XGR@#}*)zLM72a|jUcpZ@M=q=#=-OAL$$Ehfj;P;qrzj8&6B-E%N*_OOkeP3NGCj^ZC*?qwokviOzX&)0j{X{=mRyF zgN={qV-3a0h=>R&!|!LkXG@aAtyl#QD2}2h8KJ8#k6|N_gZ4`6>5Q32jCXz3jL)D2 zKeA=y=D!FC=ts=!7;0c~Y=TP~8A)NZ3`S5FHf+3u)drhVXq(vj)^)_q3}SaXLcovI+wV(G%x9oYDnCj z0krr=y!9ncA5(pX-0HRc;1w zyP%d$f(ur)A1YMN++N6()Pdd@(~8-LC0dw*fJz};|3)G{o%nLY)X zvKS{?)Q+$T63&y;s)@Q{s}!B}mfCo=3jYaf&kUNXr@}>C7#L~ zE%^RNEV5*Y8+e1T)ccV;qn%K~3``f|J`;cX#kHcHk?9nIT3FT3N>OA^0Q(a0og+WI zt>S%L7Dw5O-yaPSM)%(uq{+NWJGqZww$~8U(z?wLr0RU#{W&MW9D&M$wF-kM@=?YLZh5 zO6z71vrSIBHM;^<&sZhCc=JNXmbFz*+&VhL2IL-P*GG%1f;iCe<)97H(;1cpKHXFP z&|Edk7gW6c(=Cvbqbz%$ShP%(#~3izuR{0nKWgTPCBK*hOLgdUybR;9zUh1q`s*p+ z*3~ddj~v%)cA~-_pX-d`yj)JJB z|9*owrk78?%Y}Oh(~8f6W325)mcDB?N6OIu%SAO6swRJo|ceDrVAiBTycQDrU= znm&<>>AOmF#V%~9FcW3OReWsMg)=)c%$7xcU;#O0)xP?tGO{H`EpKjvQ%pTZk)#c^ zl^@LTYALFS#%UkRzCOEFqbSD9fnZ)1nDUzkvQZ^|zzfa?7+Q@`t6DFoL2=^_Je)=5 zy#_LeoYl%VU(YBESUO{6+p;9PmIRhD0ZX4Bi!Jt4VE!CliY(-!%Gxm-mWDq({HK8v zqZmFh#AEkgRZKvI)?FUwZ6ogv)xr(?XZmtXZW@O+3P zwhERLf>dHU4@z_tMSs&SgC`18#nY6ec3a8C!ytdkZw;%Ld-OIpyqENN+ZZGxrWVo% z#^ww;X&E2m3Lc0z_tdD($@pLztVqdSHQlP3A^MnL(6IDkH3Iv3zTXGLGth%-{dwK3 zxRQ~+!^|Y;^|o)!yHalDM)PZCxG<1;;|Or=-%I|!J7Mb{ixv*>Bgf}BIw^@h1ko@a zf|DO0>uX^qMXK+Y^4W~q-G?fhpm(HH8FbZg!Ub#nA>tEy$(vm(gfh>@4m8*SG3^)p zO2D3ydD;WfVlc78X%1pgEispHG&fWu(2Hv`WQ$cIdVVe<5xhR{F!SqjQerNLSNAu1 zYWELvRafOge;(+K*^=;x0TH5gL6T|WA4S-VQQQvFT5s|odcRM=Uw;0Dw>qwZj68j~^^v8hAK5-t@Gc$Nl&JGBnMC*AztlI_nJTI0Y_ z!%#n6^zq-2!NRD^AtP^J@4f0;Xw#|j6YY3}JGIYNGtP3Lt1q6AoG;_BQWquaG$>)I zQ9QC23uCc~SVPx`K?@OWcP74Rxi}V74q*q&E`0Y0$Rn=CNp`J%%FM4R22P7O36y%4 zCjP4p)r>wEv^yR8-(Ebg{pdjXaho{Be`>3IIq6`oHdC9Pshgx$^^@NG`+3y>NJ%;a zQxjZ>v{?im^V=RNc}0IaC(BA4>XXnH-2$C-=r|ONhXXQmD`TH+nmV;<0w3I`&}G`^ z17v(rf$JsmYAa@%MH<*hO>K|WxTxN$thQQ>_-wnTkim( zuzG<%2Eu(ziRFpWqnrp(jvrO^boNRC-L|%{=&IGnuq+WA!$*^tXvR$@{wxf9=HK^$ zO?>h1f+Vb7hzHV0hzcSx-Zy9vUiPumg#9>;Iz2q?o_9W6;{_SLEEO-0P$n3iSYw0E z7-$!jbE@`Tu(eBAjcsCB3&{8O(b)Tl@z6ME zXvduMu_v>2kIIhveac7`9M$&t z7hu;;mq2>5fj>OsCpMKQW`v@Wbd|}sj7>wX-;1lqe#V1Ooc-KY|2cXdJQ{64uaKHC za7@ewl~F^F?c~K3kY781^_5f+BPQeg>NI*$*2VNI zayzc7*(2ziwFZ2V+dv|GYKIM1TReHAJaE=jjj`%2Ae}YyX{pJj(2HJaN=I-1P_@Y> z=QPGA&@T}(F=Zz%NsHFY9{T~&^H|~6v-p#qpEf+eJhmgU`-9MAw9mwe zfig~#$y|e?{P+&lKW1zDLl;9fq~J*P-;4hzi-P~SRE$qHGS+lFvU;nF41*FyGB%NK z=eJ&Wlcr)aLe0ApIws7(;-cEM)Aseh0w)GY_fh??Je`*s+hnC4C4;%m=M^A2T5r>G z>Pe2W3(fjGoW!kPVS9khUjVYwhOHp4#O-jA*nKYBNJ&GaIX6X-T57;!B@t^`vK*42hM(Zz#9IL}K@C9)f--xksyTcx3)5+v;Dw3jiUId3Oq) zGzw8&CT<-Z1*Y5jG2;~9?iOz02n#&!gjZ6w5aM&OBml0)XK&Q94)6DxdH?*RCNUm^NJ^}rs}8af@Vn2#Mr>eifunbA$*R<`j%_s+V7yaV`tMJT3^_*arb{ew zbF93aQh&q4QZPyL;6vXPYG%;C`@sF@Kn1NDo}l-x-Fw3+j=~Q`qfFvtqJ;abERJ=! zwbMyg>(;AB8-6J&O{Y_#y5IoyrvemR4R)CN5^#M7dH?DU6RiDRAs1k2W%ZHoNLuu( z_i|K-%Wi&PB4wVM|F5d6<9{`q8>Ihd>RtDAU8OEOipvB%shS-6e$R|gaWX*5)BKEK z>k~EC@q9qf^Sa|#=~2p8)>+Ii`DdXL=#jrwMxcha9B=EjO7;8a)Ii#h@xM3_a)9Zr&Hqya z)r@NA_=Jh9kn0U4RP_P7=%yOhNL6A~1oU585_+3W(0AZ-w>+YzY3bRg=`F3f1VnyL zzgQyeEWgpm8(y%5-@@j&LPhQHyk(Do8rEwwfxIz%Y{hl%VaFpEa*2N=7OM%rI9^oP z&0S$ILEX{n`;e~`0X#LS&KtYx*gELzo;2$8O^@U$Q@AsWV$Yl9y^jK;uvb=)?~W7G zqGeiVKh4O;R3-TUC$RVyP*qp3IBydWjQ3g4qkC)F{fCyZPZn^9!*)fCn}s|TY#bPb z^tO+2Q|{zNTtPa@v_tsoz@cG%@e}i+X`=0Nvh|=tOh5fXmolp`-h{4p-y?IsdVeom z@I-IDMm8~}ccpK6wOXVucizCQQyM#Gmp4_bh6F2t1P~g22pI_n)~Pk<)w2|eyw&LA zAt&5xZkf5u;&v--IKqqb(A@ai@XP>_a^O~2a2{_L@KkgJpbSpEKX21~jYL=!5-HF^ z`Be$G9XavfW_wPyH2_Hj9*_P!yxP096Q?b zLWDeVSz*gHi>_ULpon*%-B5JYb+BAH7~4u(ZCO1mA^vC1l>U>Zkl^%VBza2Q!S4cO zlI3WseHG)){w#H{lZ*7&?*hd&kQem0@5lgVf4QEScgsl-Nz%&Pu=dX4!l*dg1uH1*i?7XN{!ipY1LS&I1CH)y0-Pp%p#frY(%_Wp}i#&YwTNBD?{!qv$7yw^AyHA$5)Z?HnFAk3ReTjHC_)k3Sj?kMykJzm&dlRi+q@ijm)k z(Tbh3qmC9O4w1s=6$UOUJHH^pe`11`I}LMIMP)5g(XMm+_H1YMRnlA$OUCWIHVr&u z>0$LQ+r&1@C?U5!gYf#od6-qM&|N`EsQtz_CU`->JBDM6n>D%r>xb{ub=Bva*n#0T zF27UZ(|At?DF07NLl{`q)5Vem;YhcKOdCx+}9RP11LEQ#6yQ?zEyyUqv z-Fv90PY5NbUv+DL%|}hQ)2GBU)YBw252ibD7!A7sgO)ZH;^NPJ^bpk>_a2VhJIn#FW4p(kY=NVC@=VczK4Z1xq{Lc`4eret0T z{-N$qG`sU^u?xShTFAjPlM4vQ(N5<8q1!}Hqxicb-QRU44Y7Q0^DZh?Yj|Eq^dabR`PO=54 z0(OkNXSPc2SZ^<$-kDmVAJgl~`Z)`St*^G*_&;zO6dh*gl2dDw#=bKq=`3Fx5qv7l=}*B zYx$(=x?GRhAb2SnTe7dVK;70uHsu`Ir`rIXOBY@Y2hE|WLI@ShHt#s*T^`Bg%~wmU zrbjc8y4H@)R^se0Z*@&wEg!5v9YJ3zl=M&bk(JjE%7SqcD%-BG^EM6?w#$y$MaBhK ziFYh?T0)ElJxt%}o~dSO(2#A53n9Scj=EdLSe4DB-t!yBukJIB1=()@g2)++CY`_N zbLqMp73|?=yX266h-s&lc*R*d6(2FSf!#!iMLhRd%Y9;mXHE4t8j9jMN)6Etw*7{p z=C@OrWmxK*w>~&Lg#&7h?WYYCG|Py;Q!N{zbDx$|zV^D)^!+zw3jYm{xpuSth1y z8rRbW^Q{uYW(Z7{aZ0GR=NBpX@L@jvcA-tqcKt~Dkc(j|&Z+*U)~(fyAV?W!34NSK<)$#3F)@jFf0wm;$9DB@!{ zDI};i;nn_;l(VY6HmlS5)&W3=*D$y+GE|RU{zHjOEfK`D9>X5pO-k;}@2V*! z1Su1167g!bkS+kXBIA6#QdpyJ?G>+aVH1~eppf;}5xV#x$UEKW>A7hwNhedVWzHZU zU-Je-r03$bnKAT+R&lrc{T-DfkEE{8ZTqDf{FzkKIGeTGiSu|d^(gT<<-ZZzz3HtC zvsY2i*B%U|yqLOy|DcSt7#*_Qx2bdtm8hEZ!v6Ln3x?hd%<}+>3!2E!tB2s;*zXaM zT8)Stm5p`ta6Cr8?>=Nxve5FWtUEP}uKHGRRK{VuV~4|!hpZuz!9-z?N1+FEixP+d9k#ZUb4wkqP5x#-aI9{_WKz8$=E__CAkSyUK?eZw)no8c=uB!66 zHXj16m_$VPZwhFR89tn5qn)G=8Ya%9mi5Pb{)Lv>L{>qdv%s=VZe*VI9O~ywE#lma@ zQ)p$u@K4glwI#;+)0q+vDN@_Buad4g8zN7ZUnqLQl>-Y9eOE1kQxVre#NO?=aOcw^ znjSM3t+xdkZ$h_jcY%<{W_cTY-DQV%h!j@i_##`ow|I!00V76A!TN5qutj z)3V_@QRC&gbVnri3<007#bXY3uwDT(PnjXH%o_K}S#%!Eu7xFIC z3)UHMVyr#XDwBhr;KJ?*hx`g{x`s9Z8xNH$MoPlQ`r52V%PW)@8HDVo^itsY!}jMR ztXF){C;Xi_@7&Z^f#uxr+`W0^pLYE7yM5gxXo1t+Ihs$^twlKRzO!fHfD1`(GQWE* z&zB4gGhx0nCNL^$X8&6{rwqNLp{~UwUC}!7P%=0}Ul75kjzYUqADlRTrxZKl>oZ-R z&T`g~QjFf{jak|QgRBsqGt1L9HVu4qB&$MtTU4?|3^L5Lx#V^Us)A;L#c&)h|ej4h6<+fdB42@$)W()*zzsm$C`=y%VCJRr~bLrk(pd%GB=zQi6PHMeuVoqW{0xF?gEX>;!OYXX(Z3Rvl@ulB0;cflkn$;Q< z%WWGIO2iF4_Owd78g+{C+w#l~Umey_Li5HPf*C`$+W6c&cvz#v*2n`qS1^#@8=By= z{R!_Zx-#`bv*C;xl2Gh7<_w2;otEE0tuQH(^cV$2ud6dDiPs0>7V`7|3mX-56~8Xa8w=EtU*UWbLTBdNMP02b zHLl~M4iyVFW`b%_I52?l#(Lq&gr5F-nw&7PWb=A1bi!#K9jK#OS$f*)Wd=Cr^o)Ta>*A_*k8ywX*|AY`vIz+51Ng^1GqKGF9o;4m%JP)*Xiches zXT~|&{3=-FH^_YiXs*80|Y=-YU3e zFQ$RcL^5+Zu<3r`#CpeTecwqn_^Qgv8tGKIQ?7JYUp2P0#^wi`@lp()s~K~2LS9OR zFOPIYRteU=YL#~9texeZMd~Yl9hGG21_amsgxE}WnwkwAGSi?7^-ZpDjWUPGE19uW zv&EXbpm!;|6RS@E%Pc@-Xr@GJTjA>hclJ#tRmb$^ZVdsM$Fi z0>t{Ov{}Ti-Y7}yYcYx{Lt9_HRk(M)daCSj+SPcb5+qAvG(GrtN5V85({^CR^(L!q z*N61ovC=W(XJbe|YBKJ~!g2){J?aF^*&3ATGfCzOmP{P?I-3EfmjZr86~pTL#^seZ zzJ?H+f4BPn{Kp`f7+N=xQxwen)@aAPt@ulr?WInpmp7rgL!jbt25+UQld)Ic3(;fs z+iAJeQEy9gGq1#8X)Erv{x0~>i0lNVonecPWobJu%dM327Yo3W921p#7rf)V5yh!k zRCNV?2y9(KD;(7ndHzDKeY&qPEYRmB>3LDek1OJqcy-l66yo?HLoy3}6-C}0fR+T{ zLFw9G4Lg%{UZcF9M30U6b|-JW2HeR^&zpu@I%BK}H>z_x8eSI=4%xa@H}wkI_HW)# z?^Q;L1p4vnux1^hmVYg-CJpGZX7Ww?wY$B^J5)Hbk#QR-m*^QSlu9_*#qKcWIo}i8 zikrnx53|({8WFcYPi`x&+5N5~Y|9{P4LR$<3H}u)I1G(jK8D&@D{5K~=1s_P-b@^j zEadk?LF%FjFP&Uhf~#(~Rc=@%B;0M3ZE2{xg6}wKfi0d6dG9*VR{dAc*k;yb_tQ!Z zIo=t+XK=9zpV_6c688@n_HujCB^2MhL1zMc zSblL5&OpAc6eqHF+^S3Wnp$Fdlq9t|>>8$(nZx9g=`uUGgk0{nke#ID%E?TDJ>@f` zt)2m!D-Vzj#q)^$W8TI)vyF5!D@z`ry})}d8NLyto4b;pHVX3{%ad9d)IzcFl`>TS zd{q5C=4F-FSima2TP-BOG`!Kc*&fD-&paTha>n&IGY+}iG#=K{W7^8st15pi9CgrR zigKzDN(rB4fP_K6@ICPv-(#ZEb$z7;Wcf+9bnJP4-e`If)u^$#h46btjMJ)1tsm~ z>{7cNsTNLFRJjzj4A7+=$nA1u`}fz3TK@q7aN9p>4?HK;1iMUf$^vpve&o8->MJ#p z%YJAuf+e56;kHg!r^TB)aLYchMTUqgH(O*{?=B@$4OufL*6Wb*UyX9)4~5Msp?%* zp_J4AyCAdMkVxstI9h&JR|km~J)R8qapG}tzw_4>6-QMXM`H}!;t)2mYrZW0{f z2`s3NyK`^eADAmQA%q4B{*BRbi*@xphd)(W#q|B2V}UlmBK!$&7Q3pj+nvLbVLX$> z61$i`w%lbKmiwx9!=2F61DqIGR+sY{i(swY#ZJOCC=KaC40Y-V4WvZ{Win#(oSJ!bFW$AAJBysjP%Q+7UglAm*)vsH?iH!K0b@5&SlB$xY0@FPuo^^QB+psRU? z@+X6Sb(#3PSb)9gwTT}$4)p3PxtMyq;M$PW7G_uOO>3yq(X%kKky;bbtGectCsEbg zwh|cIpwwDST#&KZv@TB$s>R5yTUeKS(6KKLlth|-fXPu=^+B`h%jqV10+LiPp7<&h`IkZJ?l}|Z_s?? zD!{PIIT?O@P-FV%r5p033IfhIV_zf|+_-Y(>0K(Nyeln~`ImPK3>egZKy1%66ASKd zEWBnfb`AR@S@tX;_mu*R<6Em(r|*Da)JGgvj$@LD_ED#o9qoT%8RGSZ`lq`2=e z+IQbO=;+N#E(op{Giogc^U(L3wlrHuqoaH4@77+ouK1-{hY(+IA|4k%oscV}fzXrK zet(#gCiwFwyGP=T6Xk4%rh8p@3^e@$d`YIf=+dk};f*1Ao5V2Y0`c1GXPVy5NiOMa zWMW`fQ1_8<*V_LZf+@3o5vMVQKC@Pja(xYp{xv12i|z1Le)uCJZK4LDI$e*Oc6}9X zs(y}bEoWGa_raR#vpzJ-=7D(DR@saRrC~M_!?Sw7yG`>ppc!|qFl?2jrKtZQGbUJJ zyaqD7y1f9&qt2D}B6tt}Hk=%TU527%e&rSA zwGf=f+N+e2S`@=8jv^kTUpE}v+t(V3XFA9Cq7gakfz0P+-n?eloOD~=vdNUTx!a!x`$osvYP zo(Dyr_t(0(->ufen@k=BA3cRhm^@igT)HuSdvt@hGZ5R&u_R{xR2!1;dnu;(&ksaH zZAZlnf?v*SY`Hi7ylo|L)ldQC*;O_XMR_Z$V8z?ULT`07#6^BP<|yXpea9e;^t93? zy(M95;cB~`98#Y50Qr`Z*x7pGN-%U-Y#^*C@>PFsV+ad4$vr_RC#?jkX6(J{$b&QR z4)x*|MVwr{oYRh$@Cp~|PR35H;L<`9*ZE3$DW`D7Xh?#OO`EmsPs*n1guKe64swdS z*{#uZn4*wRsjmgAN0Wp&^QXO^sE`fVqiOY*(Sh-WiywA0-wqi?pRi!b{_+L>zuklS zKDNWSx>m&g?KT#K^BkvDD%sunNUfMY7x$vep)B}GqM!dwJH@v{ERlO~*SnPo6hL)X z-md4XZ@ygmo3S(ZHUF;s2Q>70QSF>$D3LMwWbLg;NcGhDLs5v^1CLO*f3Y-=ZuJnV z<>;UJ?GP1g>35jdi)J<(08g+CitDog#@HR3FluW1L%8LjYoy$*54(S#SklDvwH{F1 z)ev65rz^J>@jmELkfBif1H5-R&o!SVPRww$h zpXP6@UhT67HU{HiM6RQ(i1sc_kDV2y!(J7fskD#Wh6#rj=O}0!V@%IS>Ec9cZ0)`y z>sQviw6SpTZ)t~xF?KmpR-iqH&Ny1D$sl~zTUB{`6DZ$tOM&qD;;YooZ2QLJo|C@$ zrUcp}`n~dxSwC~DVTrGM26pbbAvH5_Ib6Cna5+ zbK9AqJwtBorJ|bBUs?Owqc*=vw1<l~9tsZ)=d~ zf~Rq&MugVZL_b%3vJydh1g#TD^PIpS(cM0^61-SyS8Io>f+g%}M0lEcS;Gl!*Z%u? z0G@F60_6MdpPf#Oy9ZU}@rgjxe8t(om%KHgS1h*g8?PQk!occuX6gz6cHmiG$+)Ay z{Ym+QePO6u*Ji^}5#PqB%5}ieD%1Vai#d6})&{ZWitB2YHR7$|w?q7U=kvq?KG-Ug z)0JY;ODFGqj}Z^(@c*LJ1`*iywLjG~mjZgh<`neTb|+qbtdYEC2y5y` zw!|53%_~fqfnPPhWwOQ&-IBo7vY*iGavvI~7knqubJe9s=A_eFA{msMXxlV&Vy#Y) zUK`9DSe1%>Yx*AN;6c$2Y{-erv|o)##iuR1K2KIyhiN{cX7(Wg!+ z1+3E=FL6eRGMg03TV_?$e99OacS$%-7i(-u6jj(`j4=$Cx2wS_=mPcaj$f6HciAQK zqe7Qnm=l3F%15ie&Ah8N4tWTVG51Nv$EAQ@x|6DuaRO`EAcU{<ru~*sh_qU%nC&PF5 zeG`8XKlkFMITqv+;VzxA+h<;i4fqe@Kg2AB1zX@rT*@MUH3&nM7ifj^XK1He(zHi7>Bc5}uovW;vT=D>f-ADTPbSIKb;`zH%ndBnL_adv7NrE$2dx1o{F^a^A!PcO+;Z5%i!ej*eduV*2hptRf*>K8}sTBZZ^Rnx!sY0tmVlo=|rVO^OQ?J<}&J?d5YWJG_`$} ze>N1){j_X}veUzObzJpYd$aZANnY{8J}?de8z~M8XHQJF{;*edHTOqB13yh?k3S6U zHsd1MSNf{3*nVp@(Az$cnA^>9;~q7pag)?ndjC*Q9Ak@WwqCs3m2hQJabziz&VvA% zAq7g{b}O!&)Xv_h_&pVqEO7uK1vM%dK>->f)R`*{qE549j9f875$qU-q?Qr;91F4C zhQJydn9z(!T(@ySAS7N;o4`t1romxC8kh5g-Y0Ar@vc`l3Z{A6{v8*xpAWQ+&D;vW zBoyGC6az%Dqh9fClQby<9yk#{KA21Ab^nHDHr17{)D*y)Rp;^A{ki6aM}?Wf3Z@U+ z;TvcvK!q?Q*yc$%PBC}<*?{bWL)M@+{gFzs7=E+@ z))S4^v*%`xCpP%w5=7sqH*7uJIa5d$B`6(X3Cf^ms4C$WaI05SC(_t5W2W zzPy9T&LzbVf)Vo|uC8@PkEWZZF!Yd90MnR9C;x_XrX{6xJmsrsYax5t!T?$FWK^-e z#TElNX2UC;cq4bx|4+EP&?)G=@S$Db|Fr*nn*|DSGFBs(+_0GUE*@_44@Cfq!Ab5- zspd~UC06o$!#GGg_Pne(;2rQL)>b$YBA?Y`(voXg$S{Amazd(vEf?Z`ZE%kwXx-X9 zBuv6>y3?jI`(&%>rnU0JHSqYs%U;11Kis|NrB}(opB$xAa|v$>w~+;Y*iX%z!Ku9? zp#KcI`C`T11&1Y5z3cHeSYSc&zG6v2EdP{4E(Se4bJE;jZTXG)UH+Ao$y$~KwsBxH z?)QV^YHT-;vmRS~u>kUP z4TbnoCaM4Y|93illz%-JbyF0+u8Y-EJa3Wz{ZK6ldkgomrNp;3D>RV~+D@P8VmZvsqxrzWFU2cq0+RbkjH13(@Ye zTP!%7FKUN`mFsXaruU46q*kje<5>3g`!9bF4&Q{Wh^#r)$>?|F@KJWcuf(f1HlOSD zjNoo-(gTvuAKO2w(sc*gpIMv=#`SJ%*_K!STS$Yi`$pQR(AgbjdT+j8c2M_>6}EGK z%uMgZwCkf%+sJ%ShwevOe5G1AgZ+ z42tOoBTE!VS0TS;(naeTKbzD**UJXVU|$}=>kA*?W*NDv>TTH1zTSr715dIr6nrk# z(Fi@vdD<*oz-M1~HX@|~vV1TH!oCZ7=&SH%fbxqPx{*Qdx-9orY)tyu95ozw0cKTX zt`KpOF?VGhhpU^F!fIP_y1nI-kf+w^204H?Vxd(woT*W;*jz9nu>m`v6J8oy<;v-? zk2=AIk82{fkVi=2a8o0h4Gv?d`Srrg;XdP!m*l$)5Rt)(m(Z7!>4uD;0QT;aw`mgF z4*7?`-gStmo{|<9YU~+4L@x(*r-V?Bq);3J+^r?nA3enhZM6-%%?Ux{nu%+_U z1X4$@zHvB;(`7w>^CVu>uNk$Zk6%ocKKvTIdvx|!?#P!QcOoVW7JjCUOKaqaEeT(= za>^@ZPMlZ4+nxPj`9JKQs|-(!sx8$HX7oyWCs@VcQ(&e#nI2c(uUki|?awpWVpSFG zcu8F)%=z=VYDJDDUFj-_@2VM#6aQbB?pQnhS*t@;EXS#0zwmq~nQ;Gsj82Y^rXBD5)YLd3ok6$! zLSLS$`mry+4``1it8t-h!7irZ+^k~@nUxe4v#~Qae(L z)7uieANE2{0axzJFk-=F*}*Dwov-J8=fH;e^hU+-(2TG}Zb#)&4fpl-0+An>zmTbs zcDM!H@BVE<-FAZ=p42Qr{ye5~R^O}~Zo=0Xdlc17Fbsy*lG!v?%nqo{SV z{cDnpwC&E^(8uKM`>I~H=Ld2r4nw7`VyyS9q3#iSxeAB%aUev+6jdC7x~&w&N4#Ga z#P*4}{D)WOj~jc4fEGai%Dlr?S0by4RG+$JP~!Kyo4K>5g63v{A3$TLhua`@&4s&AH%2L7Q3hoN7_=B}B|ca8LSwD_4CG z=gb+mX*y-YatVK7>*5H+jU=5MMw8U_VKZBs!o&ePNzDpq#;pd_RSBS6zx<)Ldc=A? zclirjh-ZL!h6?U&Sd0~IpV7+u3d~80NWQ{^su7-k5IiJYu-odv? zkqEE#@}7NQCx^mw6@xhpSjROZoHJ|x&LO~boN3WxK%U#TjAN)|p4;d{I`!=CnqhSn zx0&>=6OM+WlleyjCkRgnbW-!5WO+Xxw~1xaRc4e%6{dPev7|{Mbv)$>w6%S^02V&* zlg>9SULEj8M@4ptHyb0qtwE2>6vs6ytTx@T{vpTq!}s7gP_#ZJH{b5tw-)-kxV^89 zDOl1S?H7)tr-?yIfv35B=RIAODpwa7+&V?y#I~D6kR9AoX5$k>R3ZOK0$b&RkUnj; z-U#+C{fm$`PM^}LW{Y%n=KOp3j{lC<35S4NukZJW_~Wo^-1c7GU}{ol zg59kQar-1!c~--qOd}P3?9!u8zzo2#1{cLRa8M!D1-$5Y=2eUBm}ivTaONQYdPYj{ zvKkq;AItDEM!ju#I@Qj=Nf=22!}H(rPvu~o3@0T(uoJ~S@pp(xx?Ls5xQ0xMPEN@; zp9CCFVpw8iwax|$=Qkm4XqkC}aeA&yy7!9v-CD;bozE#I2yV`2djUFBOLBo9^#$Y~ z;D4_x#{29Rh#PSH3h(0O!uU!CNwH*1&;|~KbHx#C_%Z&@9>z<`WC5F+(!;kbziglu z=z>~j5<$=YDCKAUN0C7zcWW<_Vz_fHnlv5q!+FOh_wPu}bz0rNK@VYmL*J>MWaYto zDz|+Y!j2Ek%ka2CI+V+Vubx>Ouf;d{a|EV;*nKO0Avv5WZ|S>T6lnI(^y9K7Rh$>X zSti8@5&|W&wO&=+L4oPiq{4;zbkWUq%i6qR64TS*NseQsW4)%>TB)5l^+q&z;-qy} zy8t6dRCep;kKYvecCP05)opdw)2Is+#wEu(e@((H8;krHy#7mzV$w`{c*3_#Y0teZ z5X%ir_N~SMo>lCZhoxI5hP3s}HH-=M@YjTV$ZpmvR9RVdH%8bJ%rcKU@+j7U7~>n` z*e9&%L7QJ}`QDa|>nZxKN?owcuuGjrX!&<~MN>YP?nL?>&&F#++_DZIVw`im$fz~f zs`djIbVSsPX{WdbGz0tx%5Chi`njHuGVjmI?09y4pf^zwj2;u{U0wnvR)*uJD>pcX zqIt*BX+#SN-3$f+{eb*2Wrs1rz5f6Lr`=n&ga7VBD6_6S&ODz1z)$`T^d_BbCdG+w zqd%;h0x5iXJBEt8S+82i=0KpluB+QyL!BO=3Tx2@^~|@R3@;$3Po31W=jybn13M&T zqt+_0MQ5Io?}pj?Cuxb&_qw;WT3p_J)Mo%O&41#+=@c|Syq&jpBAh|deyfoHeXlA? z=XoLcS^xGoRBiVYc@fxUiy`3$x1}*3B)~9mbxJzed%=)wGp2!e&-ROVp39}ULdR7sFE#SHV7)VL|m z@J#~6s&{6$oRU}4K51~iTT+tf+V8Y)A-2{Qpwe`sSgL{GsHE4!jMi|l&(l?`PmTTN zcH}6uw?qUUqbJE3jBH|@Vil`?vzTU$PD}Q@ugW&Jlk_ycJ#~w^HC~Z8?KJN)=1H0W zYJ_lw2=nuR|Hj0}&MH)R3v_3kzuxhUdaTBz1g)#S*MPb)wyByk@D=GS zjV@)QoS!>Vsl2#ZMbnM=Bm4DPeUYT}NXk#}pR_$T&)GN9tt{%xGls0qVlOOgcGu%? z6n$D{nT5vF zw{hRM_JpVG=ap+XikdG)tz5Iv3fE(?$S`Alo@d@1!eo{=P@4LqdAxP88NW^Ao?7r> zw`sS+TX8DBpEdex7^iSXa7c=?;P?BGB^rV*Tla-64Ez6lpNqZ9u+#ldjA5o2t&7T) z$qve_osNGi*{FL-;i~y$3LQi8G{9Co;82N8kDhFgRAcB;bM**;fGvExs}OeGuAfR^ z(L)WAFa=%p;Dr77WEZEe#+=NaPgC&etdOO%_dn2a`&7N zrUsVpmu#-vg{$2g1D^B@%eq}BbqE-YP+Gm1oh;>!YqJ`9Tf~~PZp25yi6jda=*N7a zJ%yj~H-?^;67I#O{!SOw3D5M8_+xfa9P08z;9rjGZ41vHnJd*59V#mS=(9HNVR_qi zK@|W<^ZM-8)7|OZX7XE`@tXsJHltg;HY$2%N-0_j#Rl@qHNap=4C1JF2*H-IL78@Hlf5!{T-U``>NxHi zl2*JT*-$Ama2qdh5Z~vfKE%@(HD1BF`nU{=GwnQa)#vf2IHTp4!@7P<1V35ZMj#Wd zDS9*M+`MJ_LOh&QJ524O*4!g;N~eoUQwojnMPj(^lGqj*bJFOvry`+M7A8OCFrEwf zPPR^@#PQ&o?D!}Bm>a|JO{`!?$@vM39f=zIMY=6a7C-k2RK!(QVQ)UJ`$Qg~P+-Io zVatdKY<)bQ?5{LQm=7!+fM2aaroHp8r#oB$8%HcrRX=m@_dY8a-RQ?B3LvB~h5WLy z&z#*JYPZjnzGD&KXbj-gzZou@GjNzY{~zd5rpmcrlch&HX#RWGxV~K!r^R{|Yy)7i zRNs!#VR_7+fgD=|Sc7b76d(_Naz5P3z7&j9XJlRn<>MgV<or?J)uhrTEnFZ9u=Mp;m;UDXbAhY|bL2U!b+>9tYq@q!?6&HB-bJS2B z+4{vJq@$uU8jkO5mss*c>C#UzK3HRKUdo9GTV z_Q}UqkABe-9^!OPrDvH2?Sa-NX>kv`_Iy)k zI#zuJDAz%tQs|>=b#WFfD%XPw7?wRH4Wr&+Eqt&FKW^ZxOos8P~H8*d{l4FTfgTvzQ3JLlf7GYtp&@$ z_ASXcs=2mYiEM4vu_%rWVvwy_yfeVgz4uz>IcPip{HxK<#CzW+){8`nl&!sISEKs}*$giLi@e^eqA$i~!8&$e3wg z;QGy&*Fpk5p=d!bs6okI`{tcFKaUpT|1~YZCUv>nouPtUw(?EYY0p=JO_Bfjm&qw> zpl2;~qe3>rz0Q9HBaR1w-n^pa-yN_ES4I5IuP~L@Nh{-G(R+x#D|i=6@863+gV3eZ zeZZ%_`%B+U4NI)JqHO~Sw<#Il!3-I*a=wbeLSin0USlG@v3zygqHA=I0~=p9zmgX! z9KPoS8q3T@io8h|v|am24$eKlgG;lOHgNSkyPs_2`sf7znNCq5TJntup@KpfiqQ-@ z1>e~8EtM~^*&froq0ey*{E1lgt94fF^wUZliu?ioZuQ5nXTK#s6#g6tm(OFf;hi7PFcAgNmpl(;WtXDJQMAp zQdY2!5UvA?`2QfQ@f@dm`Q6U$O4kWl0l*Uc#%yE`0QNKdwGT_>(%l-CR0MS5pPg;D zX6W?=e1s*myvYxuJR3L)+Vzdt0eT+~$X?DK?8=fY6C5aaf%>C%Wc!OIN+UN-rHXQ5 zP2!mUyy<=@HU{9Qc<{T7?#c>k1#UT5~IStRqOtQz<#EEadb==KZ_In_GI7X0Kd_^urwJyq*Z|>ysLY>@7Y4z~+G zZHtfM_)kvYIT%qESSxM0@F_`!O7Q%LVKK)y@!Q_OAKA_G>M0T?@4uXhYkDuALrrAB4b=tlYLt zp_F@pJ*Tcjwt)o6Jl8#lid1!T`i|N$adt3p6+RWWpfEgoFc?A#izVxFBn()T1hGn% zZI4lKtJVqYg1IduvL;mt&w8RZ<&vGx?R=( zs>atRj9YwNX&{C(;f*}wuN;*l34=2)zB+IY8{cHRp@Y}JW-grQMZ0?F7Y_bvh>;d1v-U~06?8xumZw)|#lOpO4cnb%+p??f@ zMeEhKn{J3L9W43jzSn!=9){yn_Z$?tuOkN(n!fzJ zr_euW{A}W-q(AX)e?P1juUl!9A?ShlR2UEMZo*~Z`F@$=yq{* z$(2!ge*Ba%&lJwpuUT_P(z|4D}CJGQUYXH{It10%A|;1BaRrq`WB@S9wQsL zkU4|Ba>K2I8qVSXB$r*VeYW3jBmJ*?KZ+NG@ z78|rEa0?8bAN-O@Fckm9cRI8oAMKkiQi|DDJUHatlpeu0Aq&|mH|=|E_$L3@Uh5X> zO!o8u-f0E@(b7G!lZW5-Cn&45uwhT>gkG29uS!H#60CjbtG%;%6{mQUD8u}BB7*C0 zm6tT+PyO4cO=tUlJ)FM8W?MVd-bU=C=xBkLu-Nid)A@q2_IL_f<+Bux%kK+@6plr)R%eq#q!m! zJaPNvr~c0Esi*$>?e%~7IT>LzH@o=J^*;M>6dS4{(>g?Za9eJeMTUWWisLxndMU2{ z;Ke@C9zlg~030B?31sbsW%eZpOM-$gR%)H-@&`8lU#MyO!BG#p>{-Zb>^wTYWEhNA zNyBx2(x0`JqOh?jl^QkMEQ&k%UZXMq%ADq@!p~sTl{W3 za`Q|sw|0AU*H(DP?h)(qcwR-C-Of6v9SYCdow(`ksCNM zV%*Ll6ODrleQ5`CvBO#Y$oLY%KK#_=ul>zFNsJO3Td7U!LCdTk55cN4t~DHc#>5-_ zOP^=Vo19D?p9U5ei{^_q*o1DaC4I+aYF*+ z{^pi4dzDzIb}T5ofJ97OkA3Tn@>NUk9y2=v>4-e1(dv&4`pJ#NKe>So#~!)CtOoBj z)|!_4o*&*!x=Os#buPFkDxc`|z5FHHP$5RXmr0B|5BB*6oZooqhwGeiS%bzFLaXyk z=a#<^Q1KUgDtVTg2VA}46{b}C%_TUPDMFz3d|ojfA9yZv-}(@r^#>p4z46YOZT-;+ zAyYd2PrLh|WB7{S@wt1AR|%Z{prTUMJ~OOCI3^c;KNGPI2=Utf@!=-^#UE@(kA13r z21VpjViCK}F^c*Se6g8(hjA0n;idRPmDa}pKU?pu#ML^bTYaDc2!FG$^5sxVW8}P8 z*ajChI;|(ZCPoPo{#&_=D8sQQUBtc50_l5#x0%vSOzLmjwl}tO{-wY1L^dQDUAOs+ zQ!{3NEH^qB<;^(7T$N{xx%lj{;c<_F13$dK^6alX_y?i)KJ~aA$O5owsngz$jX_yi zi8c>TUTD`OgW8&hFFFYJ=*c@o17~I-_o0%+#}u^qML3umzFlC-hRO!Jm&BK9w`q}> zR@#vOl&0XGg!hJV*)~?P8X)axaSXh`Sv01RQD8 zdbRz*bv8SF+Jn(Z(48h~)o*N%JewG|Hgi0(US83oanEBbae^}Lre!cx1W@p>al@Cq zKIVp*c1!%ozY+S}=l451(M=S|E9 ziDbipjo9&P)~HyCy+6EYOxsu$pO8{Od}Tu@(Eo$=AUZ8<25`oTCeS_F!Xm`ksPwC@hFEOpVMyhr?vr4tZ~o$FewD7jqQZFM8DGYosWc+5jLDU6? zy*{F@uRjn_Yi&;-ww=TRV$QiB8OsV^@T%7Qir*2>$ce{#)v?aZ>l&Z93`O5yqa3(; zj|;}!TM}Zuq=K04^JLCcjnx+$C=@>@^*a)0iLQ1KPB1S4-n6O&or zv~zx*WyO&==@r>vW$au-8rbVUX~-ASiPc(DVuQfKan@?l5nugm3DZ>OfeoFB^-0Zv zjVtZQCQgo(d}pvZzHAw1rSX}2>(X`)SthNiH)S2AZ`O02y{_%X!iW6M(^*^Rxb&iW zAaqTxIKkno<@|#N`RET~KgwExX@2)Y60d6QB6lgMSeE&;Im#EntJ1&7vil zbCXfwV2^c!fH1xmcls$auel^y7vk7#nzzFMUCzdN#*7D-{N}*VxLCnoVr%B*8nL2cOjDc{$ix@Ffd8KH30wYcFj| z9|EWylR4--Z+mQpB$^X&4j(aSe(PokDrT>lYTK(JG_Ct()i{}Foj*}s)vjr;yDFf;nWlbeMft~o4xcw>|G%b&yM!FPX1 z5>8D7&nB>RJX3e(?~zG=?PI<0qPQrI-%-e~U`%c`$0#QFc(EStCWj#NOFl5+PsG-l zF=N|a$HWoS; zUnYKD_xP0$ZCi$7QbpUb^VyMD=B9>a%J8c8h{shA_WiI*{LvSkB{y~9wNypL($Td` zVLA+!p^j4bDN!l_~p|*4}>D(VBSN{Ytu2}M*OX;k`7?#a6UX^uj3;|-t>O7pBYlpA9mXv z{2B2TI`yA*h0|9VS>yH$`;Zvyy-0zVyzmzbD*U=7F*F>lPjWhS^Zjx^ZNbXXhjyLz z&iB&nrQ>|?2bIaYxREvSx~w&&G#}F5wx}tMEu+3%XyfmeW}D6MNPowrFqp*g&4%!XmOwy%;*jp>#8LL3Ln`&hWUFkY5(gcxlb6GzZr{ zCx;gHaGTb@^O;JQwST;JjD=xeNA?)Uw%0w%J!sG2L0<>qGakNR*BN#`(=Kew!pN1- zhq|mwpJR>J6X8P7vmgD)gMScu|NHVm233p-lb85I z33@m0nJD1Sw>YX*>?;zsjhT747FJ3Q{3eZAA`>BxrGF-6Y@CO3cvOsIe=wm9b-^7o z>@8n{$@YiRhc~{XM<|#vAISt2Px+zNrL({CV#a(RNNo=W2%SxG`>ZkR&vfv2O*9T4 z{}?#`2w42`zc!2;1to^{^7!b?2MBUt9=d%A&f2g(k+HZX9ITrk^pqpYx6Eu~=yCkY zM-g8ScQ81=`8P=1V7W1{o+@AY%9FQW{_s!Ve&l^Wd3)V!Kczf*Y2h>!YE_E9F2o2w z)z)A>L@UR6)T)>nsM8A8~e%!KO`6PP}=EN$0*Ejn`#H6 z8Pq>=ZuEJ6)_nOAc2(0DLWH;mo?9WeXWZR6KNdrp#xyl#slk(y^+`#8<4pXBqdFI4 z^)K-qfBl9(epR+UCQsqmnrsPQ)UZG9x}#jkSq7c5uCXQEe&9y`VG~(&ARnJn);WMZ zGoe^-@fnv$+-b#NpaNt% z=47z*sqP_WCLH9DB3AAz~Pr@MW!9jOPxOj~DOS#NfF{&vKq$dklouXiTxE0>07hR_(#VyxYRJ zd?*IDtfM(%eP9d|*U@{BJAmh%*!k=%KW*14<{fGHhmR@PnZYhbSy%GEIcp&3ADOfp zhX~i#oM-qMpSxz(4T;@W5vA*TuVn^M=;5+m$Dx^UrMZm_!sawD1W)UoH)l?n7;_aR zORM^MuF%;)Ttqu3=!KJZ@Z_1W&mgrIo?xLq^Q+_KW$bc(O`e8NMY@a?rE|eV((ZTNoxF*Hv%Sf$jZfZ$f--!6Y z)wtT1srzH-!Nfsgy|%?q6qKa;0NP}QivNtYE;by@!PQ*o7!MdLKalfb5qWU=S3$r! zc;H;InTGw94n8E=@2E2!O;hG)6g#aAckEJp!=9L^pb07Xslk5!bcHyeHgS?~S{oR9 z2-ja@Wc_$)-gbGZaaj`;#uKB&iFN+1-+Jrq7k}}u-G1!He(v_h$38!JC+5bQSf!of zH4$bgII!LI$hv|Dp2Q%$q2Oem_agIwF!eQmSSub9_X9#ivVM(+Js%ys?=hiQb1xt6 ziE-j;Iqaf;a%S1GE)eT=A74=r>(Rr3?AT99+@zmc^YA+No2%$La9OW`^FYTKJg{M# z@tqg(J9go(9d|vFOXWgz@OOGM8T;9jE6Q7ZpOV-iItR zZBg_d>i~@s&(T%CxE&v2!izS1<}Kdj&`FWcI&@vFd&+5>x!9q2=t5x&F31>GNuC+i z)Qs!Gy8@|gn+jdgXWQl-40?HnH!-pdoRm$rF+|I==A%l@c(K@K$HyN19COJp_Z+|AP z%!LyBKD!uyR?6cpZfA}d@MYk7-he;sKmbJ>_G|fUd&(*Eqt6xwD|67jXGf{$53G(6 zdhuoWn74JS;?lKf%&uotF@!ID^S6z^lM9e-5I@)0pI8nCbama4hw2wy`=heYKC#(zxn&)x}d4A=XV&ZoCQ2Cd= zV{px-B^h76hSf)$7-v2B;Yf7k-~Ga)QIGxlZ+zjw|3lS3_n-e45|FxCFmT)jQSzpn zL{Ab?BOAd580QfH+|0QG>H@bNgqb$QpF+Lq6F`bCX^%{XCNOAXVCwsoa}FF1pm6jj z5cK2AlrRyB$l6L0KQ;lN0od#toYc_`F%5q{?6F9RAM@6rv3;;#f4`O(tbb;FPr%%D#0D3lRtO+;dlPE{ILXEF}pFKBY1Y4DaJQCh~33U z^s88v_`-k4QD#~lU+^HYoVR-tAvzjBoh0;}GT$c-$ZPV4)MA zJ#6gQ125~xm?nno16X*`2G5Mc*1Yq2QL6+?+QAUQeoOk-v6Vlb4$ob(EIggJUyUU( zj4tnA$1(A@oDoB@QD2HVl(lqAV>yFUh<*LBP0J4s>r5%RiJf#slTXBE>V+4q$PZSJ zRlgNPOJb{f_N~Y8Yv5N`V~PIc)_wpt-?~)i=$hJE$$$Bu`7_6c&(M4s`&^>bnC?rK zP=$ZU?tXObz0h+6UAD&?47`MmwQxMWK9g^Q6JB4&PW(oHhRr+cj*g{YFX9Gu9nu^6 z7K#~9*J3L+*r%psew6Z_akpIOIiY>*!5^D$)rb+OjGkOF-{L%ykIthb=TSjHJ~ea) zAM)mneB*ALB5@<_ZfdTXOBdOrj0{F*Q0aPB%c_FhYL zE{h^H`z%JC^+rv3Lq3~jW7)9}oRQ%`Kg}hvs%elb1!!^zucL&vW6iqRmUGDrX!^yQC_C|(n{&wci}2mguCpZ&9cE&*au znhe<0Jj^}7C{1We|3Ty4bUuFZ)=HZ^UAM)*^4oKz|2am(&U!58}dJ$KDQ({d0(1PD) z$Y$W-0o=wuZEDA8HU;*k7E0YKHo3YC&N>8F)}KS1U-4SM z_BA)$lxq;BJ#{Mk&3i7!)j24b%g<%&!(Wqzt9LrCt&0}I6!H5ezOczReBgyHU1DFw zvB;Xbo=sy_yoi&=LW~SDT>>jQ9V6L^jm*Fde{k_Z=*in>KJ$0|AF96o_0O5_#F&2e zLHb$e9t^P`x-VN6ejScmZr06Z zW7=3cmuRh6+Ftgg8teQrsp2N+2Oi>J`PlIpG~@P6x_V=`ZeFt~cdtKd@AGZ1FV^!R20cf<)vox~2O{GhIjZ3?PUOg5*@@_|;_lF8| zq0uNl$NI3F_~*m9znB}5NQh*UeBlgW-#^T~LM3}bWon-T@)3;46gRK<2f|<|xe2>3 zhm1;P93x^QUNAA&SkRB(;Wd*+SB$I{E{3NT6^n;->G=gMeo<{rX8=R3V;>Ht${Osc z8|O@f-{X_>oMZmK(D;Yw^N-PU|4%M~Eg!b#?1`pDjI3DLj1AjH%`#aZ`{AtTex4o3 zU3l_k$3qW4;=f$Sdh?9J-orUCS$43~wtCG4WAY?rJ*Xbit4|{Ha~V*2ImPl6!0RN*~JC{#UVX_B*i{ znezim2^-sYlhIBd3$>O8y_j_@!5g2o_Wr_~51q6AdPO7mDRKtek!@VO&s2 zKM{KR>36LKv=ejinZ)e?NZ|^`GCBdFq+`J0kt0q>9tiZ%q@-l=_aUSjnc-iAv*)s*bco88VlthX46&HN*8Yp)6aZw%6)*gjOWbge#X*9zY~L`AdXhg zf7HhzkPj7X(jE{ky@^4+!LJ($bM;NdhZG5@8=hg`VPR9vCC~>8nPA`LQu_V1$R3v5oD_b(OAUw4<+N zFEq4bGdLjDEC2cC{6v78jvoMcV9)_3K6v*}--0)~SkqZ2a(WKlFMa84w~svg)3^7& z=WpH~d+fO&kxzhIaW%$+7;^=a8ilXg(U9+8O8&Ax!;hSK9Pgdi&D9*p)?mK&{SYDY z&BM8Q6y>LL6kk;!AADe#ec&8)y=_v++ZE?2B~9O#7*9B|PSiczTh6$(m=pKMHV(E8 zuI$C^$Nnm5;s@r)7H{=I%vDcICWs&X$U}iEJjOnS{X66K!!>p=Xywd$O^Ve;dwShq zCceq}jiI*=>l^I(wI1c5A2MPaZZ+>UrlYI3@^A{U*RSHUNwR5@1Y z1ixbx%<(5aCUz>83Kh>HP3|%6f5#*k(OJ9B&qHp-NLAOGbtit3m^rYic<$bt>Q)B` zaP&OBQ;3UV5>nq4bHX&XLf1AnTClPE%m;sc+O;bY`ZJ!qrB3mzYGUggT{%;oX=-%Y z^tdmF4qrzKet2n0p9kR8EBQ?Pn-|35TiI{yHPt?2q_7y*xnEh!qb)ozmzQ}H7;?FX z%G;8$>N<7$YCVip)v(z|V|AU_G$&SGz*vFNkbRkXiigVrd58;Fy`-xXmFYNk;fuZU zVKVFNT$BCeT;kR}$$g0W#F*TWEaS*?uOjX}BZklUvi$UrW50B=4#o-P>b28c^G_Gg zEuWT7-COm1^3qGXx2o{0Vms&=TUXk+`d1X__dnL;{}bci<-S7LdOoc@fr#JOS7j`B z4cVtlnTg2^i_o&3T_E!l8`T-gIPLK5=gSf@C!IFkPQ!g@+anjEGZdaJf5;4PW1jO) z9J5X>mH}%nyrn-Hd{q_ITZWfOm3w#2oYLY~Nxo8NeeRWsk1ozT%3eGBF=xGmD&ldU z>G(M3dt#J=e(GQQwO@bm4?@p8!@m(4M>K|Q19i384a$T=nd(?1LyYW0IC>ovZqyT) zBynV_6@CYRg+~?}Ge_V1Vsr*5@AR!n7Y+s%0bL#w(RMPyZ}|i)GUK!CLe?gp6>t^n z5+4s5!MqoE*v-!kfcEms${_VMW}of5?rOyK1<(!py+~t<&x+mxoYyl<6R&4VaN8=9v3k%HmRK( zqsx62|63iGd}Ef9O@btA#sfWv=cAACzZ0iC%>PczdOAKBw#B9U+?f3Uj86K@MlR9_$oBgF+@tCKL1?-fbU;e=4F+TK8O<&_B^3Uhep%0f(i%;=4F)_b* z9DnjtFZ$5w2b9>TOn*~i1uOEN*MQ}f7ya;UNx$!Cm@YcNw!WMg-;33?)~WjiI&Zvu zA;QC2z8J}wk`Gdeb9G#FqHD(0Kx6cxbBbdy^5CNQ-*CQ44|SG-U*;wDWhL$@#J&&r#^`IS(eSw{@*} zsMvmVHTMB*yW(MAI|d$`{Q>v*+*tEdt4AMw#2=jKYtoo}KUM9#w=9^(jy0irpOLhU zWq4ZZU(U$wTkhw`3}%(JjC;yE=C>3#e4Deq1)1^8wdKr*%+5oM z1z&8p#*Z(2{yX?LLjTDR{ijh^FGLq$11?5Xyx2DDx{KI(7SbDEr8=7o9``{PJ>f$> zve0$0LLNDg&#@)iJhWkP@Qs^AnD*2yD?#}7iic+sg@T`G8eh%@#v+*YUSliC!EYZ1 z5f}3fp0V$PXE3nb@wGK%X$$gNibSx$=i(9AV&DI#3I__YoDGK@^KD1AIy7{&mtM6i zlQrSsQJb-<`Zk0tI-9H|4>ytV+l-<32x$yoR8~$<`;csm_rX*Z1J(WDKW+fNL}%7Z zBNm9S3(sI`={V~|Uzf~{PU|uz<@aF&-1(J(SNX5TedO7{eS6<~|K{znH#~oPnaw;o z=lI~cu>?}=Vkb6@%Uq%2@0vIkw1>m^T%xaI=*bOF_R+1r=TyLqo^zir+lQ{$%Z8IEhE7?J>$U9QgE4t>@TcfvoY1xxlXH-mGi{hwUGzF9QhU#KSnOFvLVr5S=0nGsQy)aOmA5VdKztV%a7;|Q z=V{wMbGpLm7@)0U(I^7P*qb`Cy9Pt|Zf{6XOz1L7SFDHHzq^jsix@hk533oMkS>*T z@fwUC@dCR#G^CRC*_cq`7L%?!)|&Wn2J>Y}zC_7yK732lV7a@$IDg2k{92I8s~_@D z-!@M9H#nh{N1dDT(mso1&-p@;-LVNF6ThZNPw!LtKxpT^iq#*yto^ya>NlRb!&O3& zJMZhk(epMrRGb#6%-Cz*?GK!l^R)BE0M!qMYn?b>ZI~<;8xU=A*lu!wdN5R%%JI2s$KW!_x6Ys7W zmJ<`l-}i9w9&@0@Mn4b}3x6=y7<#d69Ai6Qn1zRUo%d1lw|VG3zQ`u`E`DpoYpc1X zQ>C#3&x$)d%ZCx8fgvF4F;7`nM*44p&-+T+s2+CDN7wk}!HgM?ir41w zi&8v2C*9WC!OJ=z#~$eC3HDs`ixj>6Jg+@Jd7ryu;^2z}s3e#A8Yn3fOyY@$iktc8J?lYxTUh~V>2?r!q94~6_G>MZ+Apj{v~kK4*YBu^Bi>P zGw&)vzVLfauUR-R^6)Wdd_GXLS?0q@HqIpA)Ql%?_%l4mm;u-vI(g#+!(*pyYA^}I znQR_6ubUOQr$(>sb7PyE+S=rnCsDV4D>QzU`V?s532zg-*v}YH5U>T+fq@;rO;*R8 zL86C&&O)`b4_sbo#r9ecQSikdDtJ65A7RNRl`j0#q0L65a086b9OfBoJ^-Z;1Qa%_ zKaeVhzwM|MB*=xBcbY_kQmurIT;ng5{D66yeC4XVY@?UABld^W~F0f7rqv z-!9HUW#3xIjO`&$*KmoCOWGmvFG|~2^fX4ioXZ+>e@u+NG*iQ~W1_Z2A`zY~V?u{s z(F$)4K67f$Yoa)?o@ZRRv4$TTQzk|>Cwu8>Odwn#lG6-JoH?!M)X3=@BG*gG{&mF80L&J>ey+nlOHN3$+ucL z%GpItZq|0#OhEHqn+F}@ZR{7^$y>U%J;gK9)p#an@WWI2prU=_HB{eo~k09$3G3I7a=eZ>+VVV=0_feC6Am%OxUmP z;-R*V!2@;tq{y*udFb`}`IDTA;cY|qu@7zIJA6iDNa6LkVw+AX_=+tmM=vVU%82n; zSw=S7_*1`Fx#;t(WSWEC=l8@MMF+oV%{hN#Yq+9+N+|UjuZ|_rInEmtMR(U2JUw%~ zo{U2XM#X5{xzv&`cUxlPGA6s$W_zqi*P^`(^YCo8u6@ zwxNPA{r9WuKkbws)ESE(^>Heb<0Je&Gq8_e+Nb`v&;55!=1B~BOp{t+X{ z?5J9pSg&CFrC<8x+ne6>rucRry6*>}cRlme^~NOwYZIz8U=1vMyMKCf#6HR#K*`*k9Fs5 z%3?@PZBK!PiMCbv06}ekowzot9=v8Wj_?O(Y^KjN3eQcE#Ycx;J|xnHl{iLXXc}Wi z^5B>?vMglDiA9ik#<*FtKGqF=i4RK90e0dL`|-tbq3u#Wj3UUU zWgWVS=kO;^v!27~JTi~huGn}8+?$(%yY^M~a;Ojwaw{L6j6-AnH$nW09e+H4e=p>N z)(3C?jY0TR6HmQOvOIAhhG~D}8_(SS&A<8IZa?^gfByE}f9T_y2{UU3ZZLAN(q;_Y z`L|q*@r`q0gsqVD>+Su64c38|{fm!KaP^?ru}eI6zM(t*_J)W(;u8N*T>g}-`$@fF zr=0!44J709q`C}1!Hr(yvMqEczTf=j{3;R{`=B?395{GYUwl?ie8_oB1)jY1!Ux;Q zuYZLQtcMw1cH6DdJbO|;@e^q5X0E;`ZjP5n za_9#i%7QItT<|oH@^1hY&sS$Z5LasQikmoc)@l7qfNmQ z8Pr?G$8-EijN()K=UB#xb7WSmr=Sm2U7xF5sQs?LXJ$TglM{nAYbo7&F(2EZ+Gh-Z zSI$$gAw4-e>Qkug*xPOILv=MOnZYSp%Tvs`_cT-;Rzn>Hi}ymB2OqrfW!>;IHFntB zJ#(WA-EP@G`>S^SY>a%q*zH)3Ok}ObuT98X$E>5r(0q(h9Dm0)7|(HP6Z&PR=U6aM ztZ_(v@%PIK}{PWo~e^>|nP-8&Z*kkV=`<|1KFBaB2e)xHH{%Dk0BpZrfwE;EH zty3>_p@VnO|~#7#>;E*hJ@k$iW5=9@(@WW%m){z_-woveNQ^NyY zbtD-r#{-Z21RpX)X^@m~|Y!vGW4}xHc(ZoF% zR13T3OsUtL>a35(rH_8&W*+NQXKWWsshGS;Jj?~%$S3z|tMShVDgNpUe&peye?86r zxi24tP^OaHNX#vV4wTEr*8PgxSHJq??c*Q+x!W_({EgdVk3Fw3iyIgD%YG|H_`N44 zHt6QzwsBfH=QWCtxTUxC!sCXhu`mv>p=0K{e;gmZJZjO(YR-!Hyr~%`C!}My-&MwHCC*)ZvroGy_~z0Q-5qMehvC2 z$Ql@DZtlLJc}DVhTQhb2F=-c}VC3&Ez8fl3R_1 z#yVI0j-Ng#<_3%(jW>S0><{t%m9MTt);$j%eK4`zWj`Oni7PR4?C{&s7O6_^Wv@4H z(FwupTK%)=GBa+%C_l0uiD&ZNxaM0+$CG&rf`Ryokkbo|)|H`^3&_3lRn@85g}8;! za>mYjvKEYHj@jho#7q8R%P^Uh%-TCh$bMtNc;l;TY8v9Rd>)w2vyD7JH*6+YJExkq z=QCxjo#Q^_TK$|`{Zd0~PEr2lyvROtF4871CLi(9W(QLXfQrd|S$Bmy%y}kr#)jO~ z{fR{jWL=g^d?@Z)QM6fh&eN>d))76`75?}{q;cxGslgDQz6EoKs`+ht12pL!Nt;)=!bJJ@g+4>fo{o;Jfb^aWu zT+UeG#Yc4ZCp^KG(t8d>e84|l+gR&!6l`#x@Rwh*!M}edHp~g_((9iL9{MxCW1GTS zr5(c8`0O@otd`G5a+03jxmU=R#(K|z4{982ZQ8xJb#FrGLWgZpqX8uYWkC`#?EQev ziJkdHX43^VnS1&6*-w85e?I$t?|)xyn*s=fDl%@PYBK{7v^bXsHrnwe$zy)^BX2Po zZ~*Kb&SySBh|UJh?E}$>=V}$1cTiV9`a-QYm9GbzH!DIVV^!hiF@d&L@fxgIQX40F ztkgp`8Gpy8LG9`CsF5T@UhTP&wfII2+p;r)qmyAwR$;~z-wdw4Z{}Wu$^{pMT_1*n z!?ra}d+}Aq2i?{Kuh)I8lUVh_RvskEdzJAw%9AJdlW|_yMyDQNI*yLBbgX24;x{_& zgT}#{pXvn5dQcqM$OywcY}NPeOE8pH-pjr&vznWb;gIWtZSlM4_2n-;aeMaJpT52S z{eSEB#_#`pWOa$1uGPejn}hdP#vRq_a>)ii`>wq|JC-8twzFb1ICBF@&cl}&<#5Jc zW8sHm^XHJY%-|xg{BVt34n>WjZ!RWqGM@)CJ($0^|0Fjyg>po=;(z?+CI&_hb^bj@ zZz9GmUo2F=!7}Tber$H{o)5enzWC6%qvKwRPK>|@mi~oB_A689wqMrWwTLvtnGo3> z>yBa9__)y$A9Ptb3SwLH$T1c>GE3Ki9_Tgmv(X>H^}~_rH7pNHi!HW*jl%3 z8vW(P?!_;SB^L6>al!ta0h1$suo=BkJ<6mP-z&3xP%#GeV>_~Wu)(9j1mDEM`}jP^ zrYs7(u{Jlz`TWP)FZd_EP?oNkL8bJ=B0d*1k=kM$Tl%=;nLn0n@APy0S1RXx+Z_h;R_ClA{c=OBeK1odtX zCI@ov8iTQ=J_$U!Z1+XRX1yp3kJr~+v6p(<)EF1R*AMPFpK|8f29+fdK^Fg`r{@d? z11kUk|MW>jK~zESYqrbFa*=1eIeGHdwsFe8s-8_i4C>7#3S@da)}3@(#ue6vqe=);y+XN}6gb>GF3VsFt& zd|YCSI+S*>WDVkDbRoOQSWCG_xg~tfDX=1gRC0ONl@EeiTiT~0)cf3(pX-a;!#}QI z^B;_Q^pV>ml!qVo7jE&Renp4R$|=n6!hHDD8QrN{IfmVvBI~ankCZlk^Q!QI%QD2+ z5?KRt!>1v~$K9+~{@teXX|3NYZy)~92lYYd0e>~_nfE;9wxM8D#fgStgNs9J6KEjy zZUa2QWQ;|y%0=kPP`;fYiTeq0Q|9^sfxd0(Wh6K{xH2ExemG+RjUk7KH??ob;Mrid zoXYUQg8}gH*GBsA;Djsx{ru8YA2{JXZ#e$;L6jKf8-XO2N9_w84!+{cO+iF8e6H08 zx04K8D)j>$i01)SK6^tXSsjnj-G>JsG%nG(^oWk;n)ksY-(17*TJoyRe#nG^dEHoy zuVvWLYaMwwW1JW@cUFzeio2N5KI8F~!@FxQ9=(D&o5C1zL{|OsT>YnP@aRw6M%UQ0 z?D%@YAY5vxZFiz~?D6{g*WY>j^{`!Sa?<>5Zz` z(4W|u*>-7Tp4ikEa+gCA-@(kB4>S9c!?bpiN3oGZdq32iIcPgzZJgECV5Y4sb+Lvt zzsA9qp)((1p9hP4lhyvpQN6H&DP#XuY;^xeX>4H3y^hT_{N!2uT_mNvAm{VQF_xR` zeh_BO@=ab!_jPVGMi@IsF@lLv?Ld1Csnd5nD4Hk!dC1F8Ml3_@#piVdgX)Dvb6|l7 zyN;pOvU$L|QhbhS3~2CyDLKg5m|R@nQp!Jh5j~R^@RuSVee_Y)kNPi0 z5^JA9#6>!716ztg{WO6U9@iT)JVi>o7{EjfP#T%5@5H#grQyGrI2WZ~WvS%me&VPKI+(CYH(1*6K6C>wMZ1Pv*8wZFM<73A3 z*c*TU_9{)h@%w-O_5*+98yYE!+wI@|yGPW1#qD#SeT~)^zq9t>s;?(u3SU;9EtZ2< za`mIb3%{=9eb*~{K!fJPzw%D4k~1XdY4;FQ8DmY=Hy)&7*Du?M9rk1D^sAqO4)TNN zl;%q31j+tJfb%W3lINN+7C6e^w!PYQTZBv4@Zl-l$QzFX7JWOot{nVeNlbEZrcJz<3l&oe z3Q&Qz%Gfj@Me8@o_{@|I|dQC8~V;fANnaYEj>?8--n6YjDRbvA(9*-jzo%l`sc@Qfx=Xn*l z!S;K<_paM-{DwXV{i(ln`(AwzLQU2|zK=cdK(rmR+G0#454IB<;>ioX%HvFFgfcYa z9z%u>m*8}9yyii|4-|R0x#+aaS*bA?iY#v;{_xQ!j}nK(-+7=LI{v|U z>T!NK$F%+$Loa%=KCutQo*H1H*4%kkr7fEiPv_3$XU-oBS&wZLbTTI%?^91;XXf-md+oJ=F$D~VF4+j~fT7|N9SkL};O)7v2%A*a6JMen zpMwEkjbZxu#Cos}{&#b#^WkGZ$Tv=*MUgfrz~{=bp=6_wuH(Nqkkw&_rxacn2oL$TFZS{G|U z+Y@3LnX6KdjLy_OyAzjvZ{VIqjhOf0e2a_W*S+rdZ*P6e*KXgh4?mASqP2VoU%O@5?@C(9`kNdWpIE z_L23&9{tHfQ^cl9Om_`sU14afJvt1-evf?zS;ROIZ~j2;tJ&u!2tIsWdZ)f0p=Z>C z)OB)T&OdC5r@ki+jYn#0Foy6Lm1Q#TNpx91eQ4r1eEq3L*3cR!R)bvwYwu$Nm7G`P zzR!5hj+~jsu9q!Yms^(U{lE{-<70AzGblN4!mjwi!!tvlxhQUv+dO-~N*OHZ>-lA$ zsY_ypzj?Zd@$s43`-ii3e2uEC1I(>U=@-M;q-dNe`WGDZspKpBVLcma3>4nObGC8D zL1V&Hd#S9+IviWhAjfs$C?YqZuF?6Q^*82d@w$qD8qD1vT$yu2)EJb=CGtOe;KLvO z@PmI4`r)UZvLOdhLFoqa!-^CYXvZOfcOL z%jnCnHP}}4QC|{@IrnG=6Fe{Lz%S0?L!nyc?cvbP>g2U6?AzOC0A%!;zX8YgZl z-iY1=@xPeyg_!z73?I~dqsa}Y51QFn!4|v}cRV(Mu+6jRveqa!)7XZJ6WJUx*hz_6 zl%_-_vw{P377TCBpj$i~1e?I#&pZ)pUlTZG* zZt|bjIF@6t-}u>2=wg4IALTK1jl9%&f82#N&El84Rp}zg<4p27J;Duh$me zW{r~*+M`}SZU`+LQuU3WkOTvJCm(>34JLyED@1!J@tGJA8@2J$IYDdkun&~1JJRU1 zFOye(Kn8~j82&)<$WH+H;}-lMAHfEJ+YiIaPks`R12_K;CLb&uDXc8)Q zb4DijlN;np{CL$X`*5oqS4oZ}e#qx0J~@G58K~c2VSu`RQrossc-Fkc%fd4QUgrAH z1P^lF6FPf6ZyWI&zL>}w#P|3GElla<-LX|Nml~px{l56y<}yA&XFMItd4TKwhaVsJ z{YXN(pc9WBbNNP}yxL#R<$S`LX>5BhORqmT%TCV;k5RK8!|zHue((o>=k`NC^mXmk zSKJ;}k$UM@`{A3~uhe};{rUB2TWJof_x$sJ`1ag$uh&`^|K#HA4Jbdkq>xLjQP#TW z4Vbf@b57#B=CO17>~R!|pW51WF_NhRF?+dt5 zlc(t}e)NSe@!K&U9oD1QsfW4d%;hPo`3$i+ne9~fFFe3_3n2~&~4T22G2%Rq~BnzSaUfb z6VNy^3PrRTFF=wt3@n6R-Y^kBU!9`%O?PhQJ#ZPvc_2Z?h92o?IX4pIE8{Gr=Q4hh z<(Qumgj`tW*onHs&iH)Z_?k?}C4}6lCx(n$a~8F+rHv8y$A1Vtu@QS2O9@Z-dl=-H zlHEy=bcav1*GtrxTesGZKI;=Z=1>_K%II?eA8RnRdHp_WkH!YpJu(>mz)fPSk8VCd z@#`wA@3NuNJaDW>7dm)B3){ih{KSqA@1xDS)Td368-#9Kuhz>SuI7dTRd+ULZlKKh z0YEIYZ3{jgynMqI2J!vw?>>F|m%sT7w?FYG{=)71zVB1{_ESDe+Lqz7zV(m6vt~@% z25sBAwpjzW#Z4S2{&zM0bszT4976EOr^JY#V&&lnoRN<2DH9D{$cMx;YsdVe!O+8Q zKOkqkYm*Wij)(OSC)&i6_2EoGH#ie>AM%z9LTnRD*U|xhF+=@8>9rAFC^sp$d|kOb zxJESg)Hi;yT5qCY?BoG>7z=Ost=GJpycg};tSJgjiGRoKg9ts%q3Gl7OZ=^#!3++& zgHhGN%^YhTTj(YZtV@w`Op-< zver2t`Dw1#2Rkav`=Ld({i7Z%c@QOLV|QRMm)K)ggT+l@Y;YvbiCyOSKVR@0oAYae zJX9!d=+8RDHahz7LhO?NJ6F3VDT8D1R0p=e2K3gRlTYsX?OCS7b5HTCYx*%0oAwd^ zW^WQ#`UJr_s4*CM@h+7IrGAk!p5J@T`&Uq4&KkuIIrQPV^HcuX?-;*eM85mD@VwSjdhgb(>-HT(wd+@P^%)8bv|}^Z z=4kt_)eoLAE@F0JU=Juh&bMO1epm;K8>?+>_-m};E56!+r!_B#DRKGyJ%7TxKct4g zc#KK-nB!MoSwC{uXAv*-jlC_yeFGoH4;R|84;0YU7F3=U6SZ?cOX=CswMIeg#x`1* zU;9S&81Q^3Yf!x4_nR?Z<9J{wfw6vME_i#GgQf>gH?$XOu%y;ufqib2?Hh~uhKD50jU@*o z`oWxymjv)bw8r`?U>O@7*d0FfQ4-hSg>0FNx}NJA3{TtlBace9y0@;qo@Ub6_CNEn z72U-G!2xcsjbu15PHL|BkmJyzV9O=z;fG_GZ5v$G(M?ypn&F_H7}jPtRBk|#1SkA{ zyP&If$ps$bqIczn4;HYS8w0sf$`qNkn7ml&UNdCH@?QF=8*X`=bNAX_RzM~+A7dB{Nl|) zn{^_VM2GnEFw!5Urg%m+fo%3GVs-#lpd2Jai4adQDlbh0ju9ePlO zjo8H|GNG%cLNQjNB|HSjazid<623F7l!IQJdjadU4u7-2z0GlzZ4udIJvaTg~ znp>$OXT{SN56 zIe8Guzk|w`A+NR!7{S^v>#&paL^_e0*ihFt6kO7;Qe4=g*cQ(Pve92V%(wQFyXfHU zHg((B$^#o?wgD!^@Zm?ks`20T81C@vZt(C$qD<)F_Er8#(L?$m^w2~68{Yi1C`D_g z&$M6r+M~CB{?A@3opvF*9HYb-y|zaT6p!3v(+699!XNvk`w|b~{%JH|tZh^84eV8) z+is^`XE}0u=U&k>GC5P*#>2R3kFyVilQoh?pLNb#6=?At@)Q#o68sBTheE_$haDd} zV#W9U9|i9(Ncgb8PxG2b_I36|?$!9py31GEl2OE?+cts~g5No!f^N?ZcKqk3D11pr zooA^7cVk`OPMU6p!R@Z;9IH=IF(r11JwG9JPALB6cW$fHXU6aqA9D_{p28|!IS++X zFZA>B1iBb=CuBVnKVDF0Evo{q=F7?t@D6tSV_Eo*4|wuneL1Cx?#cR6e<1wzulc|9 zqGe0)*XQ+x$mCz_#U{jl?mfXdPZ^sO$Z__169ozC?fL3dA7A-zOOkKobM{rA3ypiQ zQ{uUbv804zlh{1_?04|1aX<7!|FIS0VH}7;^e;ntpH6mzwnVN8rUjhZ0T`gt?!^g3 z2LbV~S8=*Yom9NA3$X&EtskR?XcO+*(CDH6c?&FD7Bg2f1tOzg0)`K}8a zn52zx$TBMSZZJfL*sLRZyk6EZHmR*aL|@dy(D*!yCRb_EL6ot@lVRfF7ae1YOz^?L zFzu`dv15X%TB=Rc;L8JL?3hc__6NUwxN?Ayr#V147#b5wDRwg!`#bk~IC*WQ3(5`S z)&75k{^>vcUv6*tQ-A69+Sh)@b*y~DNKWU0_TW5A4-~1Cx$F(u#Wj)BI4JBgHXgTTkmp9}Ic*kZwFl7!t{3gz|%?Fu$nWDa8BZkqs z$#Ia*m4~a}c4`V_8_ma6CO#TRd-*BR*|RFxU0Yjzm4WpsEj}^iW=h;ThFs>1gBSjK z&$3?Gw>d`>_r}K$UD8Jk$knbVdupu_uUVhi99jD@KV27@PxE<@%X--#I`mYZ`3S!L zRF1aK_xeDNs!!W?ybjq5dH9a~oKdzCJ5pgkyw=G#Y{hPB^m<>Ku#pyem=D?v;uG)2 z8k@u`=MhEYD#Pyh2EPVo%x%}%11FB!fd#w1pU*zXID2aB&bToRc|Fl--E&@{+j=*r zu}b$f?=<0y2su&teAa+Pedn9`6(6&L9h=m#bz%}n)rr8PYNoqSA@pQV=ALq{Q@%J= ze}rlG{==_UQRg9h$J09DmaXPXzYucXOz!Xj?i@4U_`1%aJJc`{gI&iad&K{*-g;nW z-)64-#g~}v9N7gPe4(v**BX?3);{qM#{3ir%!%uO6TyR=V<;WeiB-;P^dje9*PrL6 z`fvRzsB27(LB7OxFz8~7G$Gr97a8@>^W6C}IY&GEoWc9UMQo6Jk+J_X=9s8mTUgH7 zckB`Q|8GB(A~k3G-)f6+>)>j9}uE4|C|@`Rj9^d;UB4H$qRp z+X4KwsV!_84a0Nt%94E{;nt5rDH>ZiM3OLeAIMJJ#Fp1d@dscFc3ir~ zu0pW59?arllkLMw81yRs^Pz(Sr9aX)01-BJNq$iLAcSAm8K3aGH#R_ZL$(wT_-K3c z&{w;0s|?gJu(VxW?ROrprA7sPk^S1&p1ghf(|`B&)Kfokd&3)^yU3*23KwIj4wHs6 zvvouEb7oA_tj$&Qf|v1gUm{?;Ts#C%^`CY5L+D&&{iVvcM0IcwtHi8*HrPKC@65#xecxzi ztTDUHS*9GWOiP#gww*z}@msdWx18_rNZvSS&*Ja&(QJDof2G)GKDiS=`hhL&d?V}k z_+XpT@AX@@n4_=y81LEZn)$_>{E6)pBbwT}y)MxMT|Vp$ANcn=gDv}&obZDwA9C0S z>KHoqI-P4)-?opd*!RtEyu6IFnrY`=*$)Zbmx&2H(U&-KZqtu_k7H->L?3c0>h{^d zQ_O0d^I`A%d|OVx_ZbAym%Tpw+&Z{_VTU3vY>L~wT5o@O0T#{yGXz`Lq!_3fbL?er z-S6gJn?gP%FT6I?D)EuB*S&@L#CpEr?@zmoOYxW3b&Wuin7B@7^riOsG`PYS*!&v_P-0*|K z`m=sr`}~`+{eg>kCYG#g^z^)TzM|<^FKfiFi9>TW&?N^SI%rQFIpK$|#CYrBrKIl( z*VRG4^X#o*vi+V>{F~bIk93`SQ*zJj{%{_^!}-{}mF}!{_62e2vuZ!2=W{`F(DyUP z4!ql6y;lwPy!D#c`b_t|5}u6_nJ;|d3%57F`OS&zedxX)gdTt5Nee>&iUYfDF%pu3 z{wyNnTXvG&yy5PG+6C1vo`KMt7QtKzdn8RcA!E=$A7FQ~jSaowae#a992?`RmyHl# z;LigKhnu)Hk6wR6d~OVE4AHW764|neMMgKp7B=H6JeCoE>f`Q08pp~e$eg%4Qp9@)M1{hWF4<5V3}dZ#)pk%qr)F4#t+7l zm$|Wm1+C_T-*HA;>k#e6l>*tm*FpXWzp=1}jz#(aG8XGiLB8$iIr#HlZPw=0$1o&m zgDP&~)t@#{a@f}&Y)+23%#ZHnzYlqCijy1VF^EHda=ig5Zt?OGFC%B}HAc(X;D=STS{tRKELM=YxXU%%O_U)PwSEBevPde}F~qJI&?sv^TcK?8UP9*81m6$RHqT04n?v-nmXuyAS9kbk-hZ zo+%yoURVzr!$%pN*l0U5B4ph=t*PyIa%b_2@#L;u+n)1I%wy~34;IO3&cOZUR&Zt? zTy#u~8|Rq9lA7|#cC9~WUgx71|G`oD^3VN(FFyFyZa)n7uU<+{uV5LQCS*hLJ+;`) z%QHrPl8~PW`KO(#!BKqu5S@JPo=jgH-pBsZarETOrr4a!fFN<%^wHm4;aF7K9F;7M0bATtuvW;y_kR3 z)iWAOOeXJRblG*^kv46|9?NC@h4boRZ zIv6!(Ta28#vmV9RFQBa6Yf(N*bfuAt^~~DzLu{V$IE$`pi%gzHVk7ZEO=6TUt8>QX z`D34PF2hIZ*?>G4dLL~p{ehpp@g%kj2bg8H@sEGe(^6h^WXudi?)Lxu%YXCWAB5iZ z^wUz9fLI|A{AM#Jc_7BiV+NeeltFmhV|tNnoh3L9$Sfda9hqN2oVn3`iHMpqf7tjLx!(BTMuI%TJ};r;&G__ z-H;skJ0s>E93W@Pt?W*@PHz zEn-dl!NeOsHz6?9ULShEVyu!0&iMD`FFk&H?z#V7AB6t0|5yU^IRs({nME36&id_N zY~<$3TyP;0TZvDQGS@om>BCMn4AGfbqHpVOZe`!pM!ylxK_$FV?m3#Z9bNhLA&;S# zad3&R2VNc^qXTo6RRIH-a$``fxLRIq^NtLVSd


    gN{IqlKKi<~2xbIu=sb#w*E z&0uMsQNz>tQbXlCarLJPj9EtZ(AgSOwDGSt@@ueJU;CnQGaokmp*0I-GX6QY{V<2l z`f?EL=RQTh2aP58>Q{ftWZmdNAFR~EOPjT9yw^h^dclWoQO*?N)mR1BX|E5Rp3{|m zoOrk7k5YhPyl@{IwWE>b>@hyBUC(RmSWk$S;{+zP9b=Dgp2pm3sTXs`FI|o|#lB?R zx~N6wQImP{H*(oew8Qs`%a=p>sdao`zsUkBfSEgf>cV>{sNM3~hKJ(w)i`3WGMP`T zQZf;Y`7M=uo&hvo9A1C$q0nRGdE${hOCG)KKSIPB*q-coO~*g`NL%BeM>hGVGBH|t zHG3S)=nCEegS6e3kFFAn#8(B|@WMX+8K=2N$5b9e1bemm7dbAaX6>>Ru!k`PI!iH#8O{(PaEX%Z`S;U%)u=v977J##xt$2N|zl{piOY{8!_i zdFClE?pi1|uj(XO*tt=W(D~779BBXn?!Y$yqHE%*90vnq{v>(^*G|Pjf>$TU!_}rj zq_${>*IZnpbNc6aDY`aEi>^sN>#A?)@%%|Mrn&05TbJlXclgmq&s@VAp3M6piMUK% z8!4L`Rl8rxc=b5ev?uP>3w4t=p^OO|dP&0a=%3|hu-VO5R4j>nYnxLUfv-uU>NG`AD89!hLp=lOeRqENN z;N^pw*3El1HyjMww|S^&elgZUzY2o^{bNH^-+WdK@4a|iXUy|@5oe2x4%9BqYFu>B zgT?+pH@MJw*mDlgnm8Xs=*UgGd4Kw+GG|fkd2Zrrc;;gcU3n<=x?^i@aIv2_pS~6c zHCR!?>q3X$VVMVE-H^L3x$&e8F8KBh@_Ml2Pw|?>;|Gq*%@}N)*@+!5gD^g7-g-@J z8jFpS{Hq;!<|YZg!3cBD?bT+Fkq>$ZvQ3fW4Zn2c<|cfj|E}+hp)4xl)zvXhtgA2l zySA9fH&K6>%6_md%hhjP(M?QLd?pk(wq|^h_(!$IqaS^KcqhIZBpxrkm_I&2VOZ_QYwPtN z|5Q%3KiNEz8y5n>0xmuX= z#Y}wKXK&Vvd21pxs(L>O4&|%ko3Z;*eXWd1tZ+95_(GYfn$rC63&--Qb{zI#Oks?5 zh)+4!CWj1bv z1}17Skt`zPKz?nE=;}=nqTVq~O+Pn1cqV=jHm4m-k%y{#W3C*90D&J)Uu?sh&*K?0 zd0aRcqiufaa2t}|u!U47DZ>+cp@rLoURV;FBq>EXqc&QDpF@SiC~*pJ4!9h09#QGd z5Iga|Ylhuz+XA-bZ*i4NJa~{(OQ$zW>{ynU^!Zy%Vew(gO$lt+Xx`dJVpYG81yIaq z9^Iaqv0~HA*#2hzAED3u{O!rN|M=~--}h<9<-EZ|Tjw3U?q?nN6##x6poikR5zGxH zH@wLe9`;bGx9v?l_*Ta`q4BkUhnyROiG1fD#|DV_*wfCx$oMtw+J%W6%gFX^!o5Pu^xZCMpI_MUb!FBi)aQr@ra*{M&7Np_bp#u@&~^x zH#&$_Yn2s0=I^WleOr=FT83pCiI4BK*wwiA`J8)xz~$br*UHBh#}zxprmm>?a~|b< z1p{NcSeN;#hjBE(?AmPBhh7iUnJQx`OwLSnsm>hFI{2S6EL2YR>e!~Ei(}QjaPfyr z@~CG7@j){7nNIuyI)4zx@n?OlLzQ^zt8|8 zOAC`q_A0rTbHdNIGhcnxl`|*zR_38RPr%n)$T;!Hy*vCp$1nSwcst)SmUDC>;EI^& ziYx@yv`oR2voH5s{0vrzcGM)c$p4Gq{1*@YLFk8n_-PBH2;yqxYe8cO!PeQ(O{N4C zvRw5{8@K$>;6RN7%;{wZ{UCvJ1UyOF-S=;ox5t{&g zn9Ab78=dGmaXRo|RHF6M>ben6Bps(T9T(sHrJJ_CN9DUf(b$-jjxjN zc|>0L#ydHsX?#uY=K(DbXH(-J@u0}h++3v@UuDO(^ahvzbSQtF3H|zJhot)uAR5oNgIN*@nnwDGp1);9x%6F2%YrvlZ8Bp7z<;n(-xyI=#B5# zMi=?G)_2Cd&x8Y1mhv>RDa4Htn;BwU^T9!#VJH~jPhK{sy(X-K>$YPrA8@i( z){7!^S3kZoj-jy?oylkCkzUykV~^NNVR0rWiCNY;F^C@cu-&%DRf=Qju;bZ_8OuC! zXVE2R+dAL!;K&;GtTS0>>=KjK6lnKnzo1)GJk5n-2|p!g17qd`FMCj9yiPKL;k)QG ze{!(4ElF(`$JZSxSCvn9#zobgcKTjd*(pAspPl2i#A%~9bFn>BqGIG8#l5P}HvQ|E znNK`&Z%tu+(9L|#MhfQ${x;qlcPO@vkuvz+N+vg_sV|1aIysba@ zU{;ZNeZK~K&PPhW$l3SXi6i#a<^=}yC2n0y+EPvtf98@u>>-G$)Xc?aa4g$u7klCv zY?!w$f5^e#_}(+xYvMJ6C-!V=?3J)-+cSYLyiH3WaZ4-n)WH^fU^6$EX05vh#_!o7 zjOAH5xyv44 zB6*T?N7{xHLN1clEo^jqrgd%CdiuU@1h(B`yTs9FaGni+^E>$<^p>|gF5&b8s6k5* zr~zm}UCyLK&^H-sEdmcVBo_~@>rdkfTsE|T$BK2~IJ$as&5a$sR~xp2fN6lLLYsAx z#7=VNqT4lMT)6c zY2-8mcCRDytSJWw{valbINW-HRkB{gSx4K@%MTOs(+{gW4B)f0)X!Z|=otsl-5F>8 zq^`;KRRoK=__ZEh)u9ft9?ga1!>QJB5HB%6CTo+qVmzt(TfYAF{l^mgLCAiJB$oAw z-P{Z^LEW2!M-Cg-%ggZ#5Nho9W<*T+^1x%@Q7Ip~u$LQj_N8wEbAYcJYLVjl4WS%ghV(}_2 z{PeJgYWvKQkI4AjRPQ7C5Mkr+m@x%cVi`M*ld$vQAval#DW2vTNNRF*o0>UZo)|sz z)+Mrux7Jd7oIl0thgk2Ic~BASe#i+GC-YEh*0K1<7h&~>9b(V;%=P@J4~$t4@pGKA z_F0edB|^?5u?O(eF-pUZE&K?oR>OFET6BAU-N9hp6&jf2dWr1VcUSx83MD&I$fDB?bMl`1~e+5@Q$Fy z!S1}7bHKjn9iNGDYKED}v|ji>YmmIApLjGTo}&SozOSGuH2M@Bi$Iu5ne0A43*|XZ~j@}3?KN>UQ z$bF3b+VPxuVtlNT*Jt8NPGT$m%)VNAr->o4X6@Vn;7P%5MO*{#x^|=QQYOc{_wqc! zoYgEU|GjZVcWOogi%U4F6WNZ#6gFZLf2t?M7}J?MY2ikn%9*R-yq*b^KF|5Q6h~w3 z{W1E{VZ6wQ&%f2vHCG8m&U<3^R_v?L_E^fsp1OX1_OqYkQtrS=$QH9Udb{E z#<&&28X?y+WU_7eM5spJxd4p8ojT<4G~9=h9Ai%xFEBT%!A@C5A+v_xb3=&JJ8`9+ z8Q$Vw2g6`x-ZJpHo`-kVQ^ko$TXVVLkeHccEC_OyLbtqTveR+%Dz?EQ0*9uGg99ud zh=ZA83_cVF596%Q%$rm@Mzme)!bA+-|#@i?_8K-Uzi&mZtGRtr;1|tjbNA~ zu8ZI3XRQ5AoDC=(FFj{nid!G1=p&obJ$TK1KM=F`;8%fhVRh|>>va~pWX$s=n&2Fp zo`Q#$_hj~YAH*vk9lJehHlfeeUPDR@+Qe!@>04~c*l(X(*AKp)pR;T|&<&x-zN(S) zDPI)WhdG}yYs9>3SX4d6ePH(Jw3~<2@Z<{$#*2gXBqoVDF|;AiMK>TZ+xuMk(l^@> zox}d!`Yd1=%%-UztHchzyNNAE9fgzCBk7-`R|@9QLBT%!BjS6|!X-?|cm{qq7SS~x zVnBUQfoID#=E(^@K<772Ug8Ty)%MO3d@gRVzolyyDVmO8Sft&`IE zlL^C_?bQ@^B(CfwWTcnasF5)+4)gMxv6c*EZs@RRs{hoR>n;tCFO45-HMNEBuYv#4F*n7~$SmU^?gUkM+DKD@=H{v>tq2J@0V=0d_Ti5KMY+4?Ey=7kP- zbfs7}5+2hFH2Z)Xz3z`bQNFdj_t#O*2L`^~B%Uw4@WSmI-}uJu#TQ;&|Nezf%`#^` z|JYHo{8T32?B)jEa(*jP#Gx}b`&;pR5JCAo6u2DvyjFQ2Kph$z*T|=BOXz`?pA!dO zZEJifgH$n=@#ww~b|~0V`F4cQ#ap|v6GA3c`MKK@PyG1p`(BfOBUD>xNo**J@!*A+HP6I#`K?+P+cUi34kdOeGXz;A z_Ac^+H^eNMRVIh`jW=ztJ)G!5&B)juuUXUcAh%EG(O6;J&$`EV>& zQS$hFK%nk}O@2BGrtnr~k+G?GPG#Y3F$@ux=s9tpsywfEF`fl{*N27O&QDnTAgp3L z7>-59hd2+OP#PLpI2V4;C0=JeqrO7siyBjKO-FRy2k2MP+S!6TaK&0KqvP;%2Dz+t z=6v#l42Ch}(^Xxq{ zgf}EXzmIwiXAFuQzNTL#=}(+00wqZ6OJlNzRUd8rl&tB}AECID66CD)c0h0ZFrS&NM4Ue!6bN6xs4k2gMPJo%*d zkpsRmW}fCp;#{ogcYYkt9L--#Nw()(v<6?XRmO6I)%H~ATkqUMolD4%es=_+-uO_UyX_Un8M8L&_TC&jo`HuKow0jj>ACH; ziW=6{F_UBw?|sO>_S;xX@$=7r_V!2L{D40Zdiv>S0?Mif1l=(lKv`rD>xCoXQ5lVl z`E5s4JAi5rI6%4(RP}8|?=w(oG7}pBOJFG>cbT2J>TMrL;h1aQZX+AMV9Q))A%@Bq zczR9pvElmA>i%GcT8A?3!)O))o6}gRSa6fR`5_KYDkgfjPau^uXP(P9|e=(?5& z5wHDiZXdWPIbbNGZzyfb-n_X{&drhonvJCopZR7v9~eUgF8P?>?IEE3-tYbJ?Kgk( zf4%+jKmK3dzWWb-0!to;arJLtYL8>ldk&PPH5M>AfxjovfH0IM@GN7r=7i-HWTMu30)|@=#*bsr`D%E%C+wSYrzJF zeBJdOT5_VjhT`=)f{%7;pWor^+wBY=V+>gDfel16WmjZu@Q?@q3UucWPOuA)6e(>&T?a=qit7YvmA zyEXoA8lR7|uPf{Q2wvIc!vS`|&i<_*DcMsg;pzDkT=8X}O$)py+#Ooy(fD92gQxk? zzJw!-jvdJ*2U~TmJX>=qo!4dbh^98q`?RS`mObkD6m_-XnWMdUp;2{?o$Vd-#F^R; z&=cQc}5zEAG;%7<8j_uyRQm1q-W@5)u9Vd4t zZ&rKsga^S*#e^@#2qtnl56~S4BmAj3*Rbs8)}@D5$TE7>eq#;rHKy9`@-oI0$a#u= z>-F2jeAY0<>vuXe7%XOa?rR_!QiHv_{lT|954Ro4`gE-0Hno(c*?Hntf*szh-|6p( zRmD8`9Y5;N{-P>B`=YU-Z?x)E3S~{cqhq@yU-q_^-x2{=^eeHWcTn z6>J_XY&{@3@E-P$jUS%>5R*R%DFDcrD{_?~;3%itB&<%xQs28UJ(T^>Fu&U3Pke`N z<8hK@F&xT?1#$F<0@1^lk|fJQoQpv6XJHaJ%QIgcv}?=bp>?x7@e_$+9J{fFoPlL- zH{3?94@cH%U833;oil2EjcwXc=1LK{jup#E^c$n#orz)`9lctwF2zWEHZOG5R~+ys zUilR7UmH=|>pR~9!B;sS?A7CS13TJN7icZ7G1)UV+Z&u3TXA(eSYjU>;oI6o)vr1+ zOP%7b+r0@D_gB99WyEU;`emWXuTO<*ji>S_82mIZhv!3ez0ELKJ`npRqcv=9oi|9%7OW$NAI7LWK7Y~@J7}zKD6nWQ8_20 z!Q$q#9qGs!xpM=)#>K@tRGRO^2`n0K)I+|^j_$(fHo$VX@6K@B)w)*VH> zb@6pk#@59|%jk?bI!@n;f9L1Ek3fyF$Ao=p^gDXWUzxj9+x4gWrM9y_c3X{+gwWf% zHZrzjxAXCw?-+VZwc8JL@KlfQDbu6aSWpF(&Z{y{eHP2k?Qgxr0 z8S*%9jZ;4HiC=y24?<78^+`0u1O{lpHGlq9A&mnJ^455P)bJ+yt2OiGV=?zQWDC|! z75$oCJiR%$SWY|ywcp&|U8Dp$i)2mM_Tr`w!D1cj2A&59WVtE%e>I*z!^^kRHj5DA z*r+C7ax;gCg=fB-qddW#@r9R~vXU!tb)1Zyq40yVzXn7Bvt>k)u@RZV*ZHY}e9pt! zKA@;i85i;2^P_)_52JC_7SwgTAP+kw| z`^;zm{_X8g{FU45UiWFMg41y{#)w95baV_(W6>3MQ+cM39&oxQhr9-}4)j%n7ytaL z9sGm^KNUM!wA^}NR!qRa;pep_E-K^!HF#Jje<7im0wKA?TI44;`vD#On}RoM$_v|N zVC)sgSppw;yk6KUKGl|wve=MJZTiqghf4kE{()?B=)}=|V*LII6z%atyggt154DXU zG3KGP`!V0ZZEPo@XJK6J*uW-!K$WGoulUWF3jR>wuorWwN0uD?auPF?%eX zRWFjVbL|)2sTngHI1Wr5>o|5x2eI7&? z7i5f!nwY3~9oaaNKKHYA6C+K9AAj-_yy__*GFeYzln<+!$pw{0k$3pT+qe?zQgs_A z*r>I3oh!WHlvded@7d3pJawdxo{XPFzcyO(kV0%KUmcZa+(V|?tbNCD;=Xa=Cov-5 zgPV8a8+&^n<;*%UNQL8?Ke+Tz{y2~Jj2{N2O5;zomr8riMG0`zmq7*dv}WX;dL5Sgqi&5wQTJNO{)Ys)+xVPB*20^F$F?y&Xw&qe~yW;UWqv2v5N5p=Z;0=h~BiDfS&WjT=e#O44&W$ zPHz$~jFc-PiBC#wJ0&4YM~HEA5)61vh0X4?^uv7UMA zy+*B~`O?Bb!JhF)Pbut!ePq+lc(kZREXHmzWDkRKf7qbJ#@NEOTd@SkKp883 z`3;6NJOiD$OLuW{-4etPo3Uqeqr;UivVyHC%7pl&b?>?87rrufR?qm% zT29}*dE2TKSpW1!&Q0^=LY4C=_Er2r8+6d@-!pgAkI#pU%3WKVKlx{jqj&RWZ262X zc$ha2ECWQVWT#K)qbnJ&jmAv4rpEmHg$!Jh$w8 z<|naWF{sE}ee4%+2^I!iTTU#(8pcrPOrvi-zktIi#gDWH`83d#+E^zayni+B8Xqa*qK4f%(QnDrzDMer zGtYrMi}D<3DV6IzD<4V{11lJ+Z!O(Vo3zv#qmywc2fJbefA-2 z=whALO&`+qaEjNB$m<2KH|k(2If0AQdi`EDPy}8lB@076g*nXFXZf3NywG##6XgJA zQ3sT5Bu?90DzJ3>fY=aV++Up^sQABNTH$pVK=1_dy{M5y|azvfnv}Przdc#jn&68b>l%u$(UEHUey4pF z)8IHUg_zG++Tn3k(qtdDyuPZjle3EW=A0>?=PZc**hb^RBSJ?WU{W^zeHMbF zv7oRnUQ3;4tee-=Tzav`^|F-R052suS6saZ)K)M?x6dPVtM=K_pOns+wW8ccPd&Rp z&T(THK99!l+S6rZUoJnqWm`LRnIvizdxt8FUmw|!F2!SX^hb5;^-Y14YL9~$4p zgR@L+?+NVZ%nq)|SFg{=(eG-;SNuC>j`-p;WaU!UmY?)+ru9CUm?p0n%O0()3bp3Y z930}uiVZP_E!v4y&Z)@_3Jkm_7M5ZRvd^~M?wl7XuoWNYq>;en{@{U0#s1B+Q%iJg zoA+x&!C$h0G%vJqZT{V+MrXgE;-~oD*VsAKd2g{MtT}7oY4B+Bf(hN%v$AWMHIZ)? z_Ei)e_KUF=y|Q093ldMqRAc!-n`f_nDPU!_g-{f(&}yF9kW+CUV{2?!$LzKB0cbF+JS7ITJ1*iJ z9!4!OgeQFEwU4&J{cil5IIQ(jdz`ec)*0V5B<`>dvC7spKKaZf9<~MJ>^oueGYs*e zp1tM|z4)xMc)LGGF8;vH1v|w|{L^OX?c2f@{f$HGU;3qg{NR5z?y0BVwR}cT0I8@? zKn%bjj^yz;61$%FqQ$FXM+h4II^{CVLsd1#O{X5ljZFCVAw)nCI5Ast@#^ii>yg{R zZ$ZUqkb-j|d;=K%42&-8v{LsODR9P}7%X;W%`;>hleE~O?}TZRzA8PH zhn8QRTa_AqXTXTj=PFp@YxqpIw|Tvm6ymgej<0Nj9BMpZM}f7e?_Y<|q482b2B9#QrKbMOXb z?NIR9Blgb^OTrsDk#zf9G4_*)K&U?SgM)LL{34%)B_Ha)<(#xH^5eT6ef0L|cRhN0 zWd2=cz7dV@Ce<{PKiTj0L^#05H;eT#`NJ0p$sy((_oXQE#4)dCuRj3TejX6O z?O(-KuE1j%>&t^y|L?fu71)SjWOH8ab;|t2Tzc~x4bj{26BBtPV7YsxH~_KlONznN&JX%vXOEec zx#6W)9xT`o4hR|ctM^8ERm5fZ#)g0F$>SUJVidF6@FHg;RO%-t@iCOS;Mum&Atpqk zSN+ORw;f(L-46D{cjir%J=O&sDy<>-n{NQ`aiXBILPaJkYI{ZlXhBFK$a$37epuhcNvzh*n7WrdXg#(n5KPgBZ_#H4zfJhUOQL6d+D5=H*4M>jV7IdAtAOurS#t;9rH~-Q7ZR!fbFXt8eE4p%S;_Jm9k3TSFZ=Ax-*3dYNvX|Y z;Mh#8h|hdmY2PJ3rcLL~3Bq0;j`T352eJN#s}uvnIx37q_2_ip8#oV#u@jwAYDwx) zbeNGj72-!M?0aSoT-mg=bC89@a+0y_qjWrLh>7?_9qmUfXCqRWQ)|V9_<0TiPfON( zRJ(@1H&OVoUHjyhH&x7r(Ag60N4)3%q?nkK7hnIKr*8l1U;V=EkNvSf@BdJ>__DS< z3~6n>*4zZ5v-k{XQDW1Qjh|Q{@$=gyy~dC_wu1)9>nhGF6}X7C$1D^RGQmh z7S}ug@DP{}n#6_k!0V14)`)XMvVAD=9+(fJw9#*k(u+*}YhIg>rxGvqN%p7n#9`ur zUH}_FFa1tixb9DK_GJ?kV`j9ugj7${89z!@JiuW%*`@52$jOm4JKV23c zDTWXq+Ot0XpfdXkme}OJ$69c9&AN^xYkhRC18lTyRD(19M_?KM~`Ry;q%s}D@5-Fo-_lz6EeYZX7FY+@_rYfaAFu3g)vfEU3f=l7yw zq=GMO;dgJwx|Uc$CijQfUHirCgPpvd;`Kn!;Aq?WMiyP4{NyJd{DaUt-}&?ajpCC| zLz&w180O&W4bP6uL8e)i$Q3+1y^(}xbhxPtHq?T5wY_izgTkRY0hz$$AH(kep|2ls zY#-I8oyaGhID(yI2*x~E#>e=xujoNj`|*t=%{SNm6+;p<{_c%2CWA$9WAMB6bqv02 zP&OxiYD0imx_$7Ngon+k4V+j}&o{-$D?X6@LDpEo38vsGm7luF$3`M4R}xQby57~* zV*DcWm=7BnyNkz;ni5mybumxyPd%7CPh^NsE|zxuL}-bQ=xRQ=Ej_-OyHCBuJ!YY4 zZ<+Y5i~A+~vcHaH4ky0VrT*G)zvK3?PyGDtJ7)rLu)>+p1abulk<=C_?G z#7I=V_F08IKI7JXhZZd7A=OjX)3uG>=Bw6t&S>u$(cOm~)LAQg`otAjruMy8%cpUh z2e)46+y7TxzE~&|cKSsVAC!9E@lAL3P;wzTNls)BfGd76Z>$Cu`!I|NI=&iDfGr=- z2l|X3b2FAY`iV0i82VFd@0Z#4iG^aTamQnsjgH6d@6Q+pi9v}oGxzMAnauTUpzJTO$ff)QvcBhj8!TXef+x1!%dqJPg~{hN zu~4o+_Gx7IUXgy!hQw|D7BEvI_JzWhF~Fno$orS zalt|fYBa<)W5&h{9=AQ=x^l(enAv~YD!=w?pTE8N&2JvO_tJeo2)*as@1Gk)lwc6T z>;ht^<4pSt>?9R|chKQo&RUh*Cs698TQ6McO}L5X;zJ>rifYZdFosS~?mk*2fDJb^ z);TI<&#|r7lOBQShxa7-g7Z?8JW+tnaAw1CAb>|3RnzeLAUzJS(8i3oWhY5}sCd#` zKG3n%U!htzxam7-UlrWG)(7e6AyECRts3TuQ214YCuWqP}BgTcNB^_f*DENpr7V=5+N$$C95X&vm>ggDaRi2BlAfciU+hzcHsS ztAV)+mb-1stJq)5sZE))$73ps5H;2iE&9eVb{96N{k*OJ^h3gFG9O_Nrw(tMzVUWfa|xVHEUdnPYVS8{KS+qBM*nD46dwyF{bTnYN-gE_?r91 z-jne^HGTB0JSkQ0v`=iY8C$G9dNg^l;bN|wgI$xvGyVprUSK)$k~v$Dfv%@9s&CVt zjg7lDq21o&n=kX#v+L@lADP%|NsMUw>@l8GHhND#Y;)qw_}XKK-PM=w{?y{CU-N2Q zac8UrV!m@BI`Jd4egAfCW=ye< z6==|?Y@OK?IYUx6NA8_Ru4heiaozu1Di=(l;z->B#-2ZZhVpMH%!d#7M?88b?_~?} z^!OXLVHPn*KX&M+-8r|XUw>TyO*zOtVql-*H>I(G(0ATDoTD0B{O~RtlARaG0yWW_+R!c7R#xZf1?f!~S zHz~0@ahueDH~2g?_2BP-sLg&8`S1VzTW%lu$ltoX``th3zZ&|k49{>7{)^9z` z8_Sp!;Z1yskM>!mIoX?)d0-QrKHn{+yKP>1>!tlt-|!2H&BiS2lL?ir%DV8~y43cE zD{PeqoFdztaohITj5~g*J2%!=U1HvNWwScF-}gYijlfDti|}aHz7wZ%mb%h z&JVBG%f_DEOs*zJsnd_2@fY=8W8}dho%NY{I;j#v1dI`x*4UkK<{i(xho6e^;T>CL zLND|2X~u`vdf12hL7lYsj#ufE4Z)!Ufl*)?z`T*dT`#a#wjU!>${qzXKg}<8uo;Vh;A?osW zEb?b*aCIH_%7`RZEcYWzTUcdqR+^+rL4VsR1iVxXm0TNB?Y&XEfc!($=*DIad+A@g z@gj-an7AA_MaPqbw%yoIYuZl8_+1^;nTviz;p<_>i#L2wdF|`8_xRj+J3e!FX<;Ax z)m>_z+8=!7+d8BtCm?L(*HhSp*o}V>JU(1)CvqCiqg^*e{Pb9SZp<_!YFs5xR}|G5AB1BM3Kw?V-V>(C^5&u096#$z*!mJbIWuPt=QFbAFX?UnirC6;M3Q>^h} z|LOo**3FC8*z>Pq9ly>HU*N7z!>lcjPP&7{J|tK>rKoq z4L)%AVT^JoZp@vzLA$nV-+rnXtH?ezek$NL!572k#1|9#(=to>fA_TbMn!j`4*I{Hw}ME;7e@eOPEJw#jYup$$A+85FoS>_fYQzl_ zj-Fq<*iU-lCsdup(fKjHc$((mKWRAZn{!xpPqxGXj9G8lahFeh_Q}3H)?+X(ylBuR zc5@cTM*Q3LfzJ)rQV;&D-?W2I#YZMw=(jP)y!o*(7-viJ#QCCrzg#LWHqhO;fh!cA z=#8#?Sk-uS=mnnoVfl$E1!628T5@)G{G{SBPC$*95Iqg*vUREv4&G`PH?zKHj}N}* zjBcxtw&dun*WkCl(PfN-ld<68nG1O?(UCncdR^OqspHg%-^?*~v6=GGk3Re0KN0#P zf89%93shjMWC z@OK=ew{zBCY^rwRWQ@ujZcq=S{qXg=sWf#S!davAg9TYD8JWa654CK>Y?eG|HPP*n zDY$GnwxpAdZ_KBEwCkVEW&Xs9J@>88*YJ+Hj11Z+5kLG^TK7RY2V*sctVb_K8#g-1 zZ^;Z^-*nbmB4=sW*BqvV2U>j7ajmO3+=41=dFyAE`HVHUnqO&)7a4Jd(~4#<#ER!( z(`(6lEmUiIojFoqzemj2t+cwbc3HQH$HW3gSNEYz&txI(#=_bgv@NM0Kix5FK6qyB z>RaT{)*4f}VR_A2J8FDX8?nZ~d8ry~frt;of0X(ceAhL&TOe$aBgi^`I4g9uY-Wy0u5*fA%F<{1A_f{ho(2 z`BAcM^UeK9?cy+&i3z&F6@lRP!-pEQd(Jur9uaE8u21yA83k_F#CjAF`Ht-Pwy!C%X<8` z5!>Ijmg5Be``LsK*pi_SA{2UURQ#oqY+xGbXR>{@uIx#lYeT`kvFChO;WccDhxAcnUvmgKT)A=72?gWjrRYj867JSR<@wH z%2;_BvK7}Ei|wt;BgM7kEU+kZX&aL;_TOnc9@`|N036x-c-lC=wsxMOs(wpsP69#NaU!js;DC zy^(o&-pXAwX1r7K4dnQyD)`c;%0gMwlE)q@Js=^jN&eXYE+krFNI&+*R`vT@oean4 z6({^R!`Q=@A?9;RUUZT1D zAg6f{axI+TojI@B*#6>|-gf)Qul&^Qz3=_0+hcEh-ebl#cKuN7{9vrPY&Mg-?Nejh zHs(O`4OKZX@yY{TSbg~VK{D%dQ7k4u)H&DGp%4SHI0nvN`otTJo0bJ|c%V5OzQq0- z-|WZuiI3q$28q^&pf)%&=6D`u=Lf&mM9wGgSpy45j@a6sYI}@5>x&WR)yPmsx2J|I zr7Qj?23eat@KO8b(VK|Y&p$~~yL$i%-q=ZQ@6sIijhcOG0EvHPOF2uhwPWdhMl4yQ zsk?3yz47aCOcTuE(`l=CR!*~)j2(FWKtNkqtrFd;ux5RZ3piQ(tbfTE)UWN}@{H@S zj-DAyori%{q#J5KvB-JjoQk+{)py%IWWeS%bNoi<@Mv=UamPc^am0ZB8JEhI%s;WZ zGmpk%IBl#NSyjYe9rKoGvbMQjW=vMnFdcSmW3PuFDwQ+VC$^purfCFo_Ey`wjvsf+ z&fC~bBkkCo{FJ{n6n5EBY@GYE2QD^@@6OssvD?u(eQUjv=k8G0M{X#&EI@-PK4Je{ zw~WKn`*zqnAKE?mx4n$?GUKy`p!eQYr+b*u@C9pl6VFo4A$T%I>@Met@RyL=e{`dH zADzZ0T*=k=eb1gJM%482{qTFW)Ie2q23seWyz1hrKfT`};}6stqj0`89_;N1rK-*8 zCe|7~pE3DR==(9x6fo$0k3H9C8C;t48Onf&8Xb*^^-rwbR*8*kz6Kx{5Jwl(VR3Cf zSafN8QFr!DQ<DMW<=+eMeE@Q3t?_1`ZwVhybR*sU;n#&&o2wxMPk`1=;rWlTGfGTau zEV4ITZVc{wtPdGEBzkyzBdTBQ(HR40T&^?#M8-oRPa* zZ{M@N7(T|4pZV~pU=JIz>6@a~%=>S?ar8f;WIY%o23{Lvh{;l6YJ7s3IN2f3)#iye zahNqZc+JC{{e_qQmX)UHAIxAk;WKL7$@NM|-aFHEOpJr6WZvo=e2}rsS|p!&NQobL zz?=_kj#qL3wf6HM-;gwM#-|T3eAtTK%BrD@ZBRGXK^OVaar%JYV1vx>*r`9VyKRnK z)i>_0wdFE5EKy4(TPeY6Ude*-j6rkbE-{34uTK5+cx+nc;2|$^mMBKV%O6H(KR9+> zO8^EW;pmv-L*eC#%%x8r2X}4LPkr^laRb<*$cJbQc3Q5|Z^;OkiSfi58y4_8d|q38 zR)H*EJ;ooy(aU*}vB*XC@>l7Ija5VkHnUC}AMN_Q#xMQJ3t7Z^?P0s~<`s`R$Gpn; z;yt9gxf6;nA@m%zF6cuCL>2q=gM|yYns@yID_EI?DSLSDwf&dhydTw04C?RB;Xa!* zCQxchajDk3XP5KKn1hj4^YKz^ZIE${%rCNl+G8uyQ2U|ygDwhR((Es4?2oYLEN>2j zAIa^x`)sg5(tM8{llUEH=g-C}hKbOoV6hd;g&|z1 ztIkV((PPOA`3yrHSk=IW_cgqCnMKik;2%0|p6$kl5o>i^u#tV^d@}~c>99xBTC7if z4Xo#u@|$AMcG5L3eiX}!+tkp)qcM*UKYG6KYtKLUzY%);ZBN>raG~!fTA!k zL%jqLFRO@|)&ZD}kVI4h&Ig>#yNYd#P^SRKHbt$&65Zv?;xI-Tg{laK%N*F^+PcLM zo!8BbTzPomt><|UpCfSgRlDf59;$?gx^t$1*Bb*b-X6!AY$j3E_Q8m6Ti4wK(ppDf z4;=jULE(b$+kQ-H$7z?a&in!oEG{^A6OGSUcq}xv zTWz>?>dM$FZeRS;TW`Pmv7f&Eus#UA?zNvaKI|{Qwu*^B=sF)J>lPl@yjDANy70~z zjYZPqck-9I`pq@`l?aX#P4q&RbL@#VIwl8cTd$cA8Gc{gW-t#6JDv-tSde#Kxmb}U ziwgn2Sd;E!^zpL3UEsyI^9xa5p|qMOo~2$TqR|taVc9%h!@RGd~TIqpf z>#IyjBi4KJI3DFY^nj7hiiPTY7@RnWmL0EK+8tkUn6Z6U?1H_>?;BoaPFW}qg;|^R zuz9CIRO;=q44bn4DgKEjg>y!AZk}M-*dvQJU5WST+&&Nw#Yw!@IX7TRJ`B99hpqjO zp(*x3vi`O2hjO1{4C-3PF8*ii;)KYyRB}co-o>5#7M=DSH?`-Sh9qG*WNa7T$2J}# z1GfEFuKGpO=$AaUIOEZwiItP&O7>&z)1C(g>2DlU;Lj9POzR9DT&LYOJHAWCYu7dU zW#5KP6;{F5!?^LJVGPk3EHh);GE=KM=b`Y_$IPNH=Z1>jozo?CY53wl_9rhy*29bW z^1x3`E^9qHX9S}=C9#ez733(s-}Wav*^8DJpT98XORALz$pyz0H^k>J2_(~)**A_4 zCpnb3IS)9$W^ZE~e2s92nsUIhx0?pxtF8sh_9$? z;@mGkI#jH9^jiln)sWX}^wcMu(%S?Z{4^rrff<|r(2^HfKQb!8G=0telYjE-5B@>u z>36?(Dd?{m_*>zl7=U;R1Sr&*&w+L^Du(m}y5Q60gF+I9I{uDBEDTt@I35k(EP^@V zXKqR~ask`wi86PW7lLD967_?|N)T)cOXcb}l3Q%Yp(bMjfMb`}@>9jE;YS2^i;n(c zf~R<+KZh10;L5k2#0A~plrFWIXDxh?xy<^pPNOFlu#He^+frGW$95=uJ`B9hS@%*7 z)BY+PBR!1NjA-;)CpA2wj)j8EH~z&xG`b+h&znyOzrZ(TVPuqQ=V;=gQHcjHgdDnQ z69Gm-j1^N3jo7t~(V4?1F=778Uw-2DsZaf#+uPs%jP3Wh^#xlj@rc8 zc!HqoPhI@WkKsYsFLYF&m1nxnbgdkt8<)bH98TTyRO@~}sx`NY~SQqd$ z2c})zmJ{iMeJdMUcFY&D{V5PK=qXR)pfWkpc)$W7#~S7fnf&!WYR83GOq{SCbb(+w z`436EV=X6a&s=^tcClf>OzEQ8DPGHwg(9PR)`9y1@o`RzC%GLt?}7S*46j+sl&mK{ z^jrC^G59;@2i!i`U|cATi!x_8XAHLe;f(Vpp4g#aU}Sudj;uMdjBP*jfeY-BsU7cO z9I-Re(V~lW%-cMTmudOFWst}vbGxlFI>Vdsi*65WiahHGf7X&Q`0TfQJpFHFJFTZ( z{>GqdnZ7kHUSHFkHrG3Ul;c?2tZ(jpj*s{wf&AbFt7@259)SsdQF11Fio^H2$rnl} zGH1zp&w7qtsB!oY5j^WTWl@p4GLMVq$_~EH5ypZR^iwr#356Q2UXWDOkNyh!b_No_tRlo5Y z-@yl=_rB+88#DmjD6?oN2q@DSIGt^AAl#;gkIT$kHtlIHiai$iNQ`M`e8zYwD38_GShzZ}6Gd z@2VH6)s7j4_tY=4I}<-2QX)9AF~aXY^{)GrETeqN3_vW!U= zJN0=i2LyyY*q?8rRxrUSK2GRBMfE^BRRvZ6X(3k-Us!o`Z zp|#s!Jj>dnGbgt2Mu4|{V~wke+H7SWs-Cl0C+*>Zf-h98TgI-a#D8-zxcJgy+geyYfmbkgO|!ncW_);627o^x zp7x6&Z6gScTyti9^DMnaXvmQ{^8jZW9hho`aFlyR!8>70qG8M7}(9QshTK72bi zdmdBhq0uu2eLkysxL3OvEK40D3krl>&X(~Tod>O$y5sBSopTU%%(#YEmz3aLWSo4V z-FuRX&ryxLj|OrAUn5^#+Yb1!}_aWIp>CVobDgf>ix`XhP;*Wwo>CX zHv75@Y8W%8_2O3N;}d=6Jg;}L=Zl5-fPwH>Rn|shmURp!59VIR7ZS^-J}+253XCQm z0?`eog28c9&3N`;?#UbPUh}(tEW(tk>S|oWn>_XxugFDWur#+)Gl-lnVHsOK=QWQX zCRN0w&n5L8s?M~L>sb8o6eipYZT`rfW%H&11~Be|&rEw})+P7QV#0?$>pb$vBezE$ zRiRelnUQ({Z`Mc(h}7YDDrM?hq~Ue8^?R^O^)&CS@!^EMlug2*tJwsW8n2XM(31MlVCVtuLZh3wY3}9h@4<7s~jT+15VNreXjXlU# z{hsq%*EMELj0Zz?7)O|``=siHVi#UXsGN2~(;jv1-NA)8GCjYl1GcNat1a~P;ldBv zQ@jT9qgK$%x8!}$;Mel}P3CZ1X{2I&<ey^PY=M zMSpsSP7f@iAO92!>x2hxCROgZ1a1b=@7$T^1-`_1>BX1wWyZwh`VadfXF?dV?bzM1 z=0i#S%-lYEvR*yw?6=5R98>u_Yra1K#nzIykNXTVs^N*9#MXGY2m9Uck&1iY>RMosyg(chVmw(>|XjF6dvj z%(3iQe)i?1z4~bvWR4jac)A^kG_)ln>3N-vN4!nej*Q@8<^r) z5i<_W!BuSZtrQF-+hAz|=HKzKk+TNG3XhO?qInHe&}LmA*gj5o^N$bpF^5|jMQeQ4 z$MyaD4S<_mhT4oxJygi|ee=x5rk}VF*BFoA$`gDSE~p!;#$r49)VTCet1n<#c#xlh zlbXpK(;Cu@+4z5iKK8Mny}j#QKXH4*>z}h6JeBQ+_MTx)y_We2kv}jGp8jMAOty2# zM<)m%aHL+Ort!)3?g{hw_g^7&v3}8My~5-h5w+sv94)s^4&UHqkn!jOkKQsuT*19; zfC}aG=PHjb|WQ-HL^fN|0 z_^Eeq_MFR(^T=R_8#=!N@#uGb*X_|q9&ubfJ|6=8pc zyi3NM_agAb=h$KW+Ycvp;2fz6n-BZBY8fX-q{ae)0^_zmy6# zG0Xm}gFJ-v`Mo$jHV0l#mHwGc>MBw`_o~*u_~VOcdum)^6!f{PrDY53-L!6q5+qtThcq{QsYzV^H)B2HjWyz zj?p6wxi_T!?a18L59{y^h}hj^^``N0N(8Xu%6fVhy6Clhp7RIIzHdy9;ZsyaCYWLn zyQi=48ldMIixens=R9kiiM!9=c}8*W>*e>@L|5-?)Mv5X3BY>pJI)O#ScH1~$r(aF zzIZFqo<8r|*2Q?zw>nW8j0JOSEt|vJXGPOAmW<<_K6Qzv@lx*bGrsC=#^$kgR428^ z^88jk$n*ThukwB9LmztZKcD@hKlY=bmE9x>1Q>`hzYkA516Wla9oaanAaEERH^57< zL|qJI+D9wZ$p@JeekNOM3{FF`?NIq#;Bhw3wa2b8=@Go5O!T{Z|s7XdfMxQW+wH?2{;Avh-v3j# z*Xx7OH~A0XoNE(1)=_n-{jMv7Hr7iDjniXl@7!t}iy?KXJZfF$_Be#y)-lrkYL1b^ z=5!B|%(P7IY>sUMol`po=?F!5^k&F$QDJCdSr(>0Ji06%1hABxv)0roVw_pt#~j33 zL=V-hi^ggH|0DDy=i7~b+O&q$xZuW$-pRAE>r(b$bdgWYoey~VfH)60FR86O-@o>o zdgTz9v>&sNvNw4E$cJs(`S8C#_~aj5C&!SpGY7_;ImY7s#Xb>-_>swt3E44@3^6j# z*r$e9^Xp;60uv|pfb8JIzUg~q2-~6+;i)_+Ju7w;+rjs3XZr$wQj8Cx1pKdJXveegZXJn<#>jEq6mzx)s}RUQ3xE9Bq|rhYi@PighQ zs1HS1+nrA)Ah$O5v}-^0X?^=FlrXprbr19b4PN5}pL{Y-d`3nkx`PK?j9X^vU`8}+l+yK=ec{EV@0;pFMqpdAVLO~3d{OeEZIX|@*BSTp_nCm+ zZA+TGKl#s1!KcP}7@rb{SsUxx_fU#C#piqhk4k-wznL%5%$b>z7*L4y*6YIlrSz(;f#!k;e}!GFu8eFn@d#Is|85*mKbDXZKIGYT^IuK^-lorbyOgG{e zwYgq=@x|PfS;XR<3{-j8`Ch6Wt#()e(;5^1+PV$_K8j2mD^e0q& z(*!oF&_z~a*Ec}w1ltA7qoY6C@8UaFgBQKgEgN$PVATGZf;Ti{(~Vy{p%_MQ)*>Z0 zfr*J;)~k2dqlYv#>%f8c;tMa{UU=~vzS&5HG4&^PyG~3RLmyDmL2Ycl=vo}d0oOkA zy?HB4#*sV_HrCjha5p+4H#(@*H;Hj`pHi+C0q3NOo2+9RLyhmw8)OEH*SWq>d)7Q5 zWT$!380Gp~zxCGJhd%g|w-5a3pSiv9jbHGT*GH5J9qm)^ekn538Or|Pfrf`) znBzNb^dP$raoWU;#wfaL?-l&R*6|;^dhs@ZL!KJB;vjyEJJ+2*D&&J}ts{9bGJb&O zp&{tno}4|-fWr(9aY++9)EY|; zsuu2*kBoB;XsmnVLJ}ti^Bz6pLsVyMI<$>>{G!d<@)dya+5R#gf0v!%OAJSz*2v_+ zGchh9ft=5gX!7Wmx0xx)DR)fq$uA31j|Oz=#Tz|6>!G&L*AHl!4}WDnLK~gdO9{ot z49DhRQGD~@Mx3)waQZ$nF>oz;ThV-Ysy%(5Ri2x*o;5Go{^*G=NzVGN4|3$n$VX=L zQ;5Xb4iEj!r%T$yoA{S6MFzHA*<_wvZ&~NH^Bp_#4{Y+0eF<(}e%oj8V$nmM&;E^m z%K0ll&d19+4nPSG87D7lW5}4-eHGRPp;&dqz%nC{eTTwg+xB~K^sGY8e(GHrh7qb= zV{r+V6)Wb<-#FwqVu)4mg~Y+g27}A2{if*mJP8-kAL%Jo=Lbr`IvQfTpDlniObffF^xm^SvppnDW1t%I>vlB#83L< zkz}1q^uXufEUbj$^mwjEDNP8K->@F(mo=xcr?OR>_d2|$kUmh*b&3= z7mAuv}cRg777$fKjrxOjPf*I)Va6aHff?|SAZZ;!p@97^kqK2B%b7iZ$7O1 z;DvwdN5`RVblE5K&$?zN`o~7rcoXwy9=hnoIB}~nkE)4U?^89f;hda!HlM6R`p}C7 zKU@eC4;=JkXCJP`ij2J)-PFcTY+UDo6dWG6p5!hMMwX^8KICIFzfR%5qGo(x(H#2G zqZjQw>?BuQ8&dX;bNYr|;xy~z{F{e=USQDJ`As`xi3b=HV|;q+Ks%gsZ0c#)|O__>J*-opsl1|yl9i`5p}MF(tV z9X_~-<@A_j&64XWei-x^CHH{p?SA$Hz}$}k*>8z&Fj`G8=^Y-{I9T$fY4-83 zm}+-_SdE?9XuLa4?7ZfDpyGp!!5Nl_%fw3*{3&Z4kAfh)v?`uC)+jZ7aQFo#bn8t{ zC1>ORXmH!{CN>^N596LTp)-C&fBK#PQJ8FTTEtK~{ozlsWCD4p>x2I4O-!QK=dOIo z2hRSqJM#P|-nKE|z}vjZPu^Adu!;WzCb8)miVn)$_lN~We2q)uly-B)XTbcH2>o+E z2UpHy3eS7~Kz{KjJ{E63R3`3;eb1F*cI}mR!!gu^{UA2vQhwb$e^exK3?AFJ9IG>d zkZ#n|ubn6rAum~ajS1`K{h)aGo~3w>%qU8+9v>_;B_ zSK}Uk{B7HjV|F_Sm`N}PB?oUeEeKkhg?*F_Q$O-a5;Z1j|OCcJT3qGCU=>)Cb%8W?Y4SX2Xk&b*S!xP1-7K zB-PhQjGt}=FE8t{OcS3N!*8L27@34_j;}Ddih}YRqkP8FDap(?PKzySo>D z%P>B1Z7iw8mbvl4@pj8&+n4BDBw57Gk3MSkYuy@VZkNo2#^TK7M$kM;390RhF{(Y^ zQr}#wL^5N%r8e; zPLVTAmE^0-#L_esd?$Gr-m})#wnr!Z>bxIW%I|N-gCf5(e}|=hH^->yXAf-uG6qk_ zEuA=wPG0#}e44)eswK`qDy${KiJebr*bW!`;C%wBS=JnY&HpqclA4{l) zFX9=qeXig}ncFJ(Oy6(WjMPxp%X|};%2qe(vFF#cGu7Hxw-HU;SPSy3d*6!3hAoD9 zbVgRHVw>>(t?%YU^oBiD6;RufGKkJe>AL{bwUsXS% z`eAPHdC=gd4^ONiD_!1aW9zSxG&dldzWEgH0d3QtN2 zUuwI)1;dP4LC>1R(Dzl&_rulzTKd^*>ueuAZBvVh_xN(Q>FN?~QwP6u65ktM2m-(gYAWX&)A`G@#<$nL#LC_P_ac7CRBOxT&a z*syJkjzh2|50FcrHVi$_Vr$2%_1yxGxg>)w%kg%V#^SPx=*NV4{Mp?mMqTA%f2uluY?oFI5|zGO|2*mm`7tM%f{>A$Ij zKV$qG%>CiQQqqZT{+jL!-+1BnjTiXsDgGU2ezh5s+)tt_Uw%6uCKuvH*9x^#Jh3XS znTknBjg=!RxmR_c9fdVPX!LczHir4KB(c0aGdgBq4}as`bppSAnfT;O!Q^K^kB!5x z(D-QHd)Ev3jv>Z}tCtkRU;gEP{2ly6=-uyk0-OK@N%&$A5M2aHDf}!dvf21d7qmO@ zAY#>MrNUv=u<(*21d0N1ek5%>!xJ->GF{dzw#ZCBN`7Zdx zq2|0<2Lt2L%chVXVazotLaLwM$@m+%gOtN4sjCF`C38ZR&r@`-)gU-`_(tT&F}&zPk*5OwMxY$N({J>cEV-8K_iTdW7I=DubVjD5!hc{sY&-&I2-sO`8-M7G05S*To zU5NZ~4HNIN$IJ1UyzLFkHdU-gxO=Gk8|8k1GyXt5aQAxoz5E47_DM>lvR~HOKrPwk zld1By15bvbj(3i??W&Ir?5Q(6GwwDRGHxI79USCCPiCpNmKG5PQZIy<$in58;`|hiJEtF7*25sS@mzjQgR_j4E5jl3%rh=B6onqXT`* z7gdFVY;qt2%oR^^fpzs@<^hqW`H)La$ankCg97^`I?+1p<`0G)*V=79`C;SuP|$lH z)CXuDG|u%34zt`#h8tVvyAvay#qP5ntS|cTd*iErU@6}0$N1N_2{ARdot?vuiC)EQ zQbml<^J>LHWmEa_COOCuz358qGHd2FmmkKAAA_A=OI!9uY3}~|!oX{Bu1R7sZdpgL z_uK{l=ox$D0)EiOj`PVmnG$Z4x#2o~NSB6tF43kLoueBpZfAV?-(nlYV&Www@SWsg z*OSXC>sg@B8ZdaytRC}EQYeaxb?R*!G2>X|4CWy}_a?_m<@`^Kdq3DDJJW)gJI|x) zLC((#qUK5Qmr$E{^KUTsdN+amW85 zR1I$IIp6t}Qsq2t&ZN$>4~mVqabOVJCeLUHjKOi9LCh15=-baXU2ppXrv(1dKl(=x z{z2$R-v5EMDG6$R6xd*-4WX1IO#*XM;+u;EpuoI=orK3?t2nt-@TX%1USd5hLlRmh zI=t~nL~}`w!_Ib+JUdw?5HaF5B#o=@z@lS#edV&|W7jt>CBa?@*sw?8;WFRacvSLP zLdjDWW@Ja$Gs}$a`!G5d&_LQ0V>e&*Y*}BY#vbtsPveK4Jox42=!1tfn?l^mpPO_1 zZt?iCt740#wCuxRf#5rdnAA`A)vj*hn_vBz%`6Pe6Ay11=Th2UYrWtbQ`Qsvl<1~G z?1@`#*ay&q4W314)D;`DS$n-v-f_iL|Ej9?p*#?c)>nM%_Qfy0?e?*c{mlBSabQRs z!4i3EqbuJX4@&>S7l+V_O=KewN^Z=!sC#f9e#ND64hn9@_{Yn6M?JiHIj~aZ}{C?tAoAhhEtabEeA={3E~4m`mC<)y|onFX;AJHErjmbk&Bjz*8*vO|61X z%+x1ii>V6*$(5|jI#eGL@S?8|rRxmKv^gtld8Dn!E%Ovl>HrQv@xRH13&xG8JRWr$ z{o4k9cklQt@qMwj?~;`pi+k2P-H|~IoWTHp?L(Sj-K(Es7P!OL^St*l=l87H8avh> z+RQ;{=uFoiy|yPD<%oDV@1=tW^(UYE(-7gK->e-k`${{rkv5n6 zj>q`f+Wt)4Hk4`j-8H{`@H^vMSI&LbI}c~%K+Xi0xzFZ2ATGU6s90~-#ri1ld3wC} zWs^reA6+Nz;&W5FP#2;ReI2sc@W;R8LhqL?=Jh4HR=>DU)OKv8Yy*hk3x&8~KYiPS zU-~TSBE?J{(i+%|V7psQr3q9MT z&e@TeL5zc$J>=iW;hDMdv(4BlFE4t%C)>c-TK6Z_UL)>Pvyb_phMy_)8Ry=WzZRP3 zD@t(o`OjY}QFHHRpUdv~1q!@iZ>rKo-{{2;e5=cLUWt{2ojP4l&@Y1WP9uR?$ntqa=KJ8#80s5b#I#C#RV$27* zNtB%svdJQ|_{OLr!%k3cU=!K@m$P?$x;4A1`?fCKEif|Z0u-{GRKQq9YF$z50)|K! z?8@JfFLCZE+l8@7z>0AkId)YlcEy!c{svb*$K@o}rCU=T&$IXYp7(fRr7LkzqB4Kr^c-;;9>$$eUZD9E zG>tn^X7P2^CHi9z-sts>1>HMi)HB6HE|xQpdLKyB&;B>rrZ2bByib zIWTIYcG8Br0gMUbyr;d!7H!35m26|SHymZ#GcT{hkF9gt*arq>k3-uBVp-hLl|!Td zr$7#n940wz&<8!>H$Am;fFv(GE}g&s`|rE`?(hE3w}1QJ{tu4-M<{CupVw2JU_qxv zhhpQ*$$a=`Pvxhj*baXAYK-_g`DzVwnHaRxmlC?LUF?lL^*U&zFj0(6I^GMDm+(qU za#ekQgKMSejpV48{OnP1gJ%xLu9^LqIjCn&^8uyq%SI@C#-+CX)C+yh2k#eVs}~+s z@Nh2VW|A1j*7!zFPTaev@zHvWRWj0VRA3t)L&3H5f!}(;kM5j{%x7JK-7>tyJ1WHE zYieKcf%nwN*H8P_esESV{N*WO-}?gadV`gAb!1(xIRhhWyl$$Bjr9!9Wlwbr%iv`fX)`v_%`_;_XCWiD|=E*Sbj3taVYguT|a>o4Jy&)oa`q1PYk`IV8>jP)l= zSNw@@ggeE;^I21o2R-pA^I)MQ{n@7_gO*>Wlsiga8KKq=6*2eU4o5JkkyWd zQ~^EbLF`hPXkMVVAKJVB(HY*>F>==3vweQ)ob3-@-}~zW?J4l)i(+JnnebsNhK->Q zuhwH7R=+6r66?$#=hLhMEY44>g@0oxsmEo;sj)Zs$F6N0c(BV`R!}^)x~B4pT(HsD zfbh*WFh;*J<9l)0=J*rN@=nLJ@dab}Jwt8NTfkQFX>7z`<`!HR*l(ycZ4 zicqBH?gy_;>9Xx!sWEUF&GyOsx&QdfiNjYL5}A8sjm7Jhg0KFGo7$DNeM%h=G2Z8x zt}T2TDj2idJHq}6=(GJ_c>SLkSD<|ne(~SnMn~CHPFP zSeP8b@YBYJj+)2H z!?qS*$IhB^CUfl!3u0Vj7n{^`=#}6FE2Zn>16OOb+xU_=)Zg5I;z!~i{gh%nfiPae zZ$D@{7Lm=3JbJC8@x!O8TmBVqa5dJ@*@lYAZ3?#3|Jv8zb$jl)|MvFO`+xEF#y350 zJvpeO&-r<$t5lsUrbk_Bys)Y%Q*@9g2$0~GjZ1k?KMa)epwN+}HRNO!z#~ z-eKSL-xBmEiC_qCWYJ$*v1k6YsbVO+3`u;g)d>Ia!Z6r+_Ti6Rr#;ST35<&eBF4NP zjC+k!(wFRtea6t~f9D{K-mkJFPOp)e)ka>vvTm*!A%iV@c2q+)3?Ah2+82{C8? z>yrmn;5FVk45n=j7OxIVNH*=-OYUgsWJBl36Nj(9@Q&MOp844A10VdQ{AwH`!f?$U z)stV60gd%US%+?n^t{2c&=btVT?7(H*@?N zac}t4`R09(MNM>}F1mAOobk<#hHuY~F&M`%{?N+>veTyJkMa*}daw1}Y&n}sX!G>& z?J3Tfj3?jsoZ)ERF%!Ohwo$^c5Ld4Y1B`W!>2^{@HS%it9bIn6uqk^dvF*7T8e6k2 z;Y+SZQK+%4%JM;7_ZF!8@Qf$ae93utf9^#VcGF>>4yvmkmgpV)jI8!aj5C#oqkPc8 z&*3Vw)CLzNA8h>KG4?{y--qDy?A?3EY@!Qz&CST@L$A;MBL<7WqIuh%nts1PEUv~4 zHV91KOD}!L=Vd=&6eE1ZU()V_)|iEToo~axa@h5_Btp_{k1&y}zT-c{HK zbMLFd=&Jp}qCS|<*uY*L#EyZ5X~_4D@ukHK@Jco@qaZm{%;U%6r)_!=Ka>7&F#XKQ zuY(V!`cofAU2M9au}sap2px$@)-^wwOzzQc9>eD|51S}PM#cNjam4>qZ*)66u`%QR0>B?ik&n;DZ=PT;(VAHkbD1V8M(sJqIv3y1wPgJ0&pvd{ zANLM~kuBELiBb9)+rHx8#DisZZf>+7v^{JOCa(kWpS3kvKXUPhdXZTq3pV^o@4~4x_EkK$ArFda(&Cp0=uoE zAarq{mtUUR*Q-urL*AR4Iyfy6u|+Z8WJ?mYZTyZyd>%m^# zXWNI(n5eDZU}^*M9Mc+$4kfdbiTKZ7lVQ%x@Xfy+ns1_-Q0Q*ltsh+~7oF2D9%;5d z^fI#Ms9~5I7IdyPKoU{LW|O*&jOx9KXU^j)Ry}cI6AM@R!ARcvhNJm?pipxoRXovS zvPP3JtKJ){cF7sxpigYzwM1kf$4P_++eMcOqx?kZ*=K*{_Wt+(qW?qHutp2g`EV0{ zkNBP1Eo!mHLawDHH#SFj#W#nL)|UfGhf(|@j^u$2?6&Pw36C(vlx7c;UJu71d6M;- z7!4mW=dT~}(Bl8Uf`i;XqBk}gSL5TxGq1(P; z-}&O6N^)$Rb!;rBDeTi`ELd}6r0@B`(_f*??_qP(%6dX;eN^lh@6qQtf}NbQT}wo_ z<*UP21dS5jK8RR~{!t<~ee}x?ZFKq^wgIyYAN65}w>o~&Cg%9cKAPJ5P9->V9`y`4 z|2@RzM%5ZDBis8z@tM>HlYKFqjMK*#&ktXzcqqPsg0cEUmi5{N7jd!vA#04%rJHGb zC*Pu(GeBSU@*c$gJgiSKCgpE(BM&vS&j%dJ8E=f^Yd*9jKZqYT9n*Kx+M=PaXP_CnL)=S_EMJ*sRj?d4x;9^YPS3lCnBpPQ}q8o#D(Bjdc7Gtq}(e1T3MS|Hn=xb;CIF*|VS zW!no!{7NZ?jIFln9_mf(2M%M$K&5L{d$V3Jmk+qXJa#>YtLZ1!7BVknb2C=TSY)8{ z#^i$5k%!D{?Bj#&AX~c}3gNXhof$|!hY`LL2a5Zai*3~5k0rpM(lwxc+I-=Kcileq z^sn50;zR%C?FWD0%Nl>RV+db9xFJ&)>f->kj?RUwb;e6syWG$^w{k&+eb)aqyg$vv zuXAtbP?s!k^1)gflR-emglfh*cg{1$doCzT&CK`6en**j)1gy=nE z-uVkJ<20t-7()YT&q>aDStIMWf!NUtg4H)m@ToRs%2d0oGyZp9cz+%DiX{X4=%PNc zx~KNIXKLTPM~TqEDCz@NanyG6)$2CO{XnBQuMalde|-*1ul0+>3O_MV9>>SC_`w_= zUaFB_Ye?Mc=PFSR4U`8cHZxf{`aO53^TCb0+Zf=B-T2mroZN?xn0xH>Gq$E0D%QOZ z8Uy$`MiHkaQt{v}{S#Yqn&H?L2Ip#dMd+H?xie$TBhxXO)}hk-IY6=(SqtSI+=HoS z{5E9vMfJt!nR6wRjAd@tRm0VZF0>VgpJ%}1cnS|=%sY<~^YG31(KhcYGdDbaPPnca zu?v4N2A|OR4bgR8Iw$Je;NZ(%?OKM<+zzb9R5F>Xb2Vmy15_(mmJZo+HD{n0o$8bqei|0@5E_2ZAf_V&6bp78$@;RLkZNJn>q zMgUpl{Vi_4We^WP!7`{WLpDv6?ttNZo(+dp~yj^wS@^ec-8IyuINKUlect z>KK!!kGavLB;T{v%;8gW#)p~O^@GD)(%G}dh|Yj+D>v3z8{+0!+HK)KeTLHZjEAn{ zdyVOX9Y*F;H#dkEQ&%5{`2iYXk$HHl?*6;f)uT84%AjFuzuF4kSYeNyWIGdgmx;UA zbxLS-NS6yQ^d9}Z>2LlS*2NsQzjSmg0>db>N!fNsG!38>&jYws7D-=kN~{;>WY^8M zuroSy6X#6IS=0|mk?UHAvJT0!o<)HJFtb?qc_#QKH8R(Diq!O(C;ptLU``-KG{F{gJ0xg3ir}uZK8cy zf{+V>(MR0iRbk&Pm{@c>8cYzFQ@KLr^&h4!nadTe@fk-q%aTP z`9XqW3z~Cm6eH)kboiNQVzw!<=>3E;AeS#WKPVZl9rMd}F{hs|8BQPa@5*%Fp5H3C z*RkU;e=KO_MdB1*e46`%8qO7X07>oYnop@z&%Uir?+?|g;2;9_|J)xXTG)5nQ^B%v zZ~rq#A;+*W_HDCg?9SU=(C&-nOPx>08r9!ASWl=TwGV+uBW{<_wJ`?g!}`#w({Z~P z+&pk!aEhV}+2|c5DzU$4 z;!hqg*eqJ9fbmNjt!Et+dU^grb&8rQ{Uj~j&P}o&Ns{E<_Fc;kRrs68rrKs0g4#)yvC zr(oD~pt6bBf#8!S&smoXam~TBu}3EHh@Zi5w%v4lZI&5>Xy!p6_`R92Gn*QF97y~} zVg0`Vf$@P)r~d-BP@bbI~lpPP6jp5=k^ZOvdDA53b} z2d=TGtPeqI*AFRL`23B@-26`}R@Z|AKGvp~$SFSzu-~!62k607dp3DM#5Q_!BTnvj zFIw;6C-VCNE;Y?e@57hayG?C575tx0s)J|Ry%}PUn@N7HBDoiA`67gz%uO%&unnCz zQ|jb*_C0OJ$^G=_=7!*_z>fT@tTTUd`$gCOAg(dnzzn*n5MVT>3&F&gaqzO=mat#U zrJiDe88a6K_PG#$(q=4r*f0G8r(bf6uCa*>{Qh>DzQ=-@8hiIN(~G)CQj-(O$x}A? zQg)8TcG~7riHv3S_S(5HDE(@rPkk+5Km+=s%bk@2j-Q6SH)c;z%qAQ@_onz9^xCIv zoGPPx*`+47sy#b=Qff|Yj$5kIDBpC<7rU~LP31d%&xx;n>z=*9{xP=dLAx<+Y%QKu zz5UK_dQkEOOCF5T6ucutsc*I!48|sIY1efefEOFmgAMP$>H9u5`wrRcef2$VC!<1_ zF`k6uS`Pr!3flF=qsM0F@&j8g^dWm$B9Jt1;>Q@{%vq(u0kb zp2KH9d9J?nm(*2>&DQqLGMg_XD+3z2<>6q}JH#9vzri=_LM^O`7vu3|tomTO10ZAZm>je8{L?Xt-wHZw4WsofM7Ueen&Y%I;9 zdYY@BGepI4ojz@`;BWW*T1Uqyc!5(p(T$w7tL^GRJCs>3^9~>S>bsx0>;Kq{x5%rO zO@Haj7yR0@{5m>0U@W7vd$eWW=g@?$*vr~x-P$()w2SF}Y*R2%J9p>oz|ZK~^0gfb zPfFIPWzV^#3uDM9PNnMXo<`=ApZwILe-L`tJKrf`4#OUPS=3@}a48t-zc29vf?fnW zAOXC@%nOhtPr*_&X@1@&m|;gjows z55Zvb0;yQ3$Z~nRJzdkrzaIvuazmAE^Jmxb&OfFWPxGht%cJZyl z(eiLdS1IceSqlC7NWXTeSHZ{8&ntxO>FHt{#^tUFjE>!uJfaD4U3zVG>< zdg6TEL}N)r6Z-+-q3rkZ4V?xh4r1wezQ*EdXWjExx>$dGpp9rzI9<%y#1A@^?)iKKeXzM>rD=v z{Clu`VADRZ?tPA|!unfg|9gcN3|`M@kcZGk7rxiLI=>RJe#)(ap9U<;YaczVD26EO znl&#S2ir+q`>_{W+!ONWUH6w7=)tD-D8~6oF!qBXe3?hJYocQ_T%yM@a2}3t6C2Nt zEy%bOBXXqUX(o2o<5)m8vV7_n1*{=4l2mXDr@sZChZtVYS7cTC;9@+gk z;Hy1qpqa1Z|rhK2TEfQP;Mh%zg8Yt+tz)?67uliLQ#DQzUYQrNrpJ`>qmL0&X+j(z?Z!Q zpS4v_EVy=;ewfr3Mw%0!=9KrC>YlBMVdTK=doi{ggN^O9?N$t42riFePxHwIcrzAd zBDFoVCN|ycr?xNjCExho7hTL>b&;FAk*`sQj^u8>e5$Y1lhdA`^Rxff-Zrf^>d}2* zgxqG_)%ZPm8onst8eB6+{5$XW_+vixYj_CW@MmuGX1sIw-4Cy{HDiV0vBcDoWqR44 zIJ8bIat}Pu2VQFM-ZVNHeD>K_@T+k@^;17Jy^yi#a&G<-z<3bwjTvx0)Okpa)8~Ut z1MYeNp$Xk9hzot};h%5(IL~IJK5la9>tPBJT^tbWh&~^Q((g^kIL?UT4~g+$VCv_v z4z?C33(~&zn>PaWg_^}yWnybQ0cHwL zO4cU+)6X1@%{{hs;gvf52MAGB_P5EY7usrb(`lhHN^Y05BcC}+DQ#jVor9l)lrc=y zA8HpUS2z^l_v0>mtZPkaAw0lUoh{p%wtbHFY z(15yNRTmSg>lZZ-VBIr~`|?-3=(ipZaDf{0VBt{ne`Mwl4?HMl4ea(B#w7x2L!CG~CLbKSjalT#Oe>if2JrJ75~{;2RD)}?Mgu?9Q#^Xs{-UweDp zzgGO%?J*VBGJ5e<^5ctts!e(E+y3_UJLtwg2O=PPuGl9qt0reS|9L15Qy)y?KYg&} z+u?8BUgU$NKL~Iii9WvY@P7dP7{BtI4|ut!L{H;_x=q9&>vdloLs8{6p1n2(w)`Ug zy@zGJ!sn(s(Tg9+_Z@fq$eBXgz~}UF8*%F;=2CY5Wkzs>+*CPrvzKWHOG@%Qa+a4Z z*2*8agoXW=bBXz`SJo))JvM3r7)9!PFR?excSc4Z@x*1nF^SQO#?W;iQdMxuElK94ouHwtROXFZ3zhE)w zf#SYtu+F75MuH=81Pj+%Yz$U@?(P-d+K3~ zd9{-_8861{`R1`_jDwfeiGn9>u|V%)UW>PEBGMvtJz$?nDFZ2?pw-1$OwF)X?~0g4c^X zb;&vyqb6_@w3PInoRh?f5afuMSZMI(*SK^*&aZQwHzEXUzq+a8AMVxH=!EcCoG}v> zHlLrOZ#0}Zdpy1Z_Rmvkke@io7~)5D(!9zR%Uj9>R7 z7V#qoW7<)RPCv*VcpLLoJ2sI)idQ#IZ}RY&?Eh@cDTax)u^UP!Yms*OuNe4HJU0yR zvuP(c*XCnQB@cwlw=cx0Mr8+E>wq*Uqsp{(!Q-Cm@>5gRfh4`o!MT}Y^DAF@$L+Jv z{q5WP{1c%sEIy)AKd9{kW0;}mMth2Z4>ulYuD|mg%<-FtE9(4|LvcXkQmP&Y7`*u8 zwU2yc5>v zA+HxUpv(t<;~dOc*Y_d_8>m9&+_nQ{q`^S8OFS? zXk%YBI2})Dba7=LIG!qEJ@iDEKbR0-)g`dyi;u43{<3m^KtpHz8{?*8%|2zn=BICr zbs?7Y_d zh(9_IUstIP`xGDIn{=oT8OPMY53ffoYmXeCtVw9;=Gnlo8l za8Ss#{00q$KWJs`uDcFdd+sxOiN_j7zrh%9$K3GPUbBh2+fxp|JSVD7FfU&kNA%`m zBA39s*MIv|pV7fSUvgt;V=^f5dek+g<50#XH->@Q9-zkRrbM*IEm|Gxh*! z?6aTy%%gu0`k9aXjN2$B*leC%cvzW4G6)Wf{jHQP1|3Sh0tj{9tVxQquAZ>B4%y$? z6ttNOFLI~8Yd{+$W1gD=g-vB$(|0-g1g7HuY^&(vT*H2FrEFAI%llY_Ne+`a{R&M_KyFh z_{NiX@d`=NG#dwF9Nmzob?Hr)eh)D7tM9r#&RRkA>wk1-JZ(0YXz*s-T~qyXJ_)x; z4CH=tFhh_=xQuM{Enla6{p;`2X8fDC4}Iuw+Nv_uxD zdP#=;;9rH3Og<1qNB8*|gXV}7SyyxZTH=FiFw?M2&}=fV{5j7*z&g*z5A2;EBqPY% zm$Bzw{1Ko1cD?nW6F_~K_Je|Du5`cN)xXz#Xy(yr%kJtzZD`0bmZ6e3r!m-68~yNN zqqZU9V{M)flX0kk$={&LpWd*;rt9cGAAXl#)_>J$iyF5MPqaqeZkyk4*|*)<56(+? z!|$6kow132pP4E=a99aY)FRIUKx0z^vulpEU`WYY*oMa==F^7S1%^(p;L{*Koop;*Hri+FmV4ay$-$Q!Ick*GE%H=#j)cf1#73a=t{L@mtu;Ggd z;_DBqVze3S9s{Lz9Y1S~4aRi2;~pI%f6;;rW3zvB=5WsD-x$8+FH!i3Y`z4`1Gz0c z>`bxk=&z5Vj5D1F{^ZR0r6sStxkP8iBlv(F`;}O_4SvdC^!P#a!kf7CdCP^hV4bFh zo2yZ2ZOY3S@{qBqFc;o6C5)NN2UFVcgZ=Pf*1YHI@@vQlMzQZPG_7yzVcLERLztn_ zQ83uot9%rnQ97$KmT}tUK{WnR4_@~(#yq^(w2VsSQ!-z_TK0XEB3-I&gV*S`POh^S z83X@d*ZT5X0{OCqdt|Ufjx{=wu%MNr-8Gl+DDQ^Xv89cl)2_Zv77p3J#Lf4bBX+iP z(6i5d_R&8G{n$I+ak+tYUELf*8CX;MpypRt_(lRp3?_?_i%8>}S7mrJn*~eYLd%wj z@!G%O_%{$NsOw^E-I2{h9lzR_4|()M!3}?sod+Jqw~qSY#F~So$pwcrEc?|}y2sAk zgMRHXCpepC`aKXJ&rciDESIH+>p-`i9`sHM#%8WE{s2||*kWE6Wb4Cn1sT1Pc;*zT zt+#Dh23uKUxU7S5v+9bC!CJDdIhgX{FnImz49p>C#;Mfr=7F+V(VNXtfAVmahxh#3 zj`_7tKiFq;!&f|DcRjzR!-nNo!t&FMtUo5bKU>F}BAZ_PY*=M@k^gUy654NKfjtd zfsy;x{waBWV(y%s{3KRZMXkp2!Fio_Y{87Zu0e9zc0>!mh?YfsO>2#)N{%EpST8?y zW8yW`dih)g1A{f8Irq^+9M!CS>-HOeV#7J&NfkGVy{~ja=s61H*u>D(BIc3ft#)uW zX5<-bAAHo2i7pR{sCZE1;XmiJ>iGi3YwVcj+x7JUQThR471)#=+w}Ux*Rw#*wfclu zMBO&wC;jdx@@;TrI=M!YMUQZuzA!c8&V$-gF%IG~=ZNhtelwH6su*$%DjXJ%icz*oNE!*XXPcu;(Y9`wu)p)+?-exE9tqS8~tD zS|={ybz5UOt8yk8uLzSwq<=k`=iT#OMFE%3T9EQK&fuj)XU;A^7f7`%#F638m*UYC zx?=Yl! zt*33jEwkmU?$Bd@RTAT=o!_2xZ63!Y?dUEpY@JvpcQO@oX}ZNLaNKeoihgQvbet=) zXYS?D>G2dZTB{G-r6tgxkTXdMEUfua2`$aaWXf_x#dVTbF_h`$h+?xxp}l;u@POIZMVj z?5M_WDEV^QV=TEgYa{t`m*?~Yo|*O7I)9fC@7SRD;SPJA1Ghdj@~gyt;L@C4miK%s zD@iT#tax%R?lprNi`vQqQVI`D_CYV^A!C+2#Sca5uRe6` zNNgFWJ*9+x`waq=8cDRAXA(7Wq_I!;=8MLTIJY0p(KmB>h~8^$Lt^Rv%Q?I2ejs7q z8b^2cfo&Lfh-UcZljD-u?~;dix4|$tkSQdutK$NO@zJuwfLGXnPqjMnGjI1(4c}ln z^~S&0v|rMH{^Z;CigQYF6hCHagIM(pk~;J50vayhO8=BAmbBwjpX;F97fOw{mAb}8 znrf#NeQAyEmNN#4%bL>*4ZRl?F>@DE*W8RVCC1AK0<(0U)<&CNsPSoROEf)BW3yXH z_pXQimr%oym}RXw6E6N}O;3Cf^NIDGVZ3ZObFq&MYo9L`uxh=Yr=M7r;wNLualVjX zuYuRhqrWuxe&=`o`R%Q5eXFrNj2`+y=->UwM*|S2*o+2trMN#)b`o z+8_Su`XZx`nzwx`uyL!z3)AL_4fU5dfs`>%^p2|*s`BFP^!gtXT*B!R}LHckmbOT zj>nKsOILJE>Dr%TP_E`4kr{W@*|Q~5M;fLB?>UR^UB~vUi`w}R369J)evXM_k$AKu zp9CyUg^-N`uI~GSj9TVD2s?VOb}2bP&SfnTwj_E+m&erhuaJPzXHw>&oRP_Ed<%hF zMZRFoylNN+(+fj&kb8M}aqcNT=GAy&WH#66vJch~J;o|~{t%DdiJ8x>v0<`UWT>%g zJ@AUH@kmVOON!UzFY4jH`3`+X;JqzfQwKMG(#}oQCK*>D2hh=ZlrVPAci%Nhm~KJ!pyW(|0`9zxGFOR>#LFc$`N5YMv?r7mXn%E}Y#$=v1- zS@-B-{rb~hujSIOb>ah1<3mBGitV9e=|K+PBs-W(^jXv9KPCF|Q%^s*SzE=LhqM3C zIWe;=I=o)9mn0hZ#4|qizP9&$=1jOS_BNp>V-N0?#@wRD+xrtEKD$lHbxN=m-!A5o zp5@nIvW$5obHvHxM;jHzlQStlxyiqE%x}=J7UD#y|Mv*nF%+IlU2R2vU**2}Xt z5ozA&EZ&}P>&pyYs*%eZc@<)Ex3-Ou+nVcrqH9cn9?DN!wK~SLau+$}VEZYIHQz+& z)2lYjWB#_N z?S!>1cVbJgZiXgied^|5y@^wOOw1@K4}r<+jxDz_f{EydKdxkMm&7$UE%2#-tUmP~x=T9>Z?poD!_lpY<}UIi<&MfIwY%Z_UrjV~T%(sl9BHzt*Jkd40(d5{A!Scv(k9YQYh)t#Kv zzMX@W0(R@hj%xO79y)R(Mo)NS$G)NyeJCB<^o@P=1aoq*y7-pcA0ou|(jVqS_F4P~ z6gW@5&3_yyrWGUn-s|P_Xz-Jtz8RlefH`4sN zNOZuzZTDf6voW@jeUIZOSNa1AKjjV?~bbDN~22!jJ}}{8|;>u zZ#fxGA6(%{yzA@EwbOpjosMPRt|2%h0eKwp8@$e(1XOY$!=< z8@nxnXYC8-WWavvh2H9@@1^SReA?8rH|Z>sX_(XFclO1f+2m4UmU^TvgbFCU53Ysp zHM0lk=RTvp$HG(G$<^R++#I{i`Mgvef5zYOjThMBNpN%i_`z)KLgrOL2QlL;$sZz` z`~TPyi)GwT2ldX;F;tIlvv>_&G;~2Ak7zs#9G)I_ zCb330db1c_Bo!yrBtHDrRXdu9_qw=ssW;&n<9_HFzoN6a`T!Km(>SvD&R5v#68VrMYcv1*aEj9l6o!*=W+ zn5ICeqfI>ejczw3h1_B6B)+Z+P7ZmuWgX84=Bjti~XAzt2Uv> z6=Sq18-Mh5c>)RSMbM&jO8$K&vnP#8Q$`{_M0&e*%oBJsd>on8c-s`Bo`<#s9mV?Rebh6 z1V8-J;mm!@j*k4~Bl{t^_Wn%lwJ-FcB{)FJLk6~EckTJ3oabgsbzAS~s?E5+ z&z$I0F~>>QkK&Grk0D^bhZG6vD%L za|Y%=_Rk^?b-EnQYS=Syn(@rS*m;&Uo_ADzvOBd(sb zIwfXSh0}eb z|Nj)F>+KlXRDbfH4>JCOL|FUND*DvmVePYi_&on+PqL^g_P7=-M^ zsAmCRj^In~l@nXdvj)BY*$2x;N43D$wYb;@lxBk$oWTmEW}Y@SR3=7NY+2?a&^R=Q zM)VkGpon-_&vs`1$NBQcf6QV(4}h;2u+uMZnr~Zw z?AiiG>|;MvNZvf#pBCndz5bZQmv~N0!K~sqYMf6~)f3Vp}df{<@^ugD2&3;zaEcwD2%=vQfwR0YBzCkLYpAX6CyZrl2 z{6QaFOW=%K{Ip$B{j%?@t=i0FU+q0e&6k7iTjv=17r*=eJo>N3X)Fr38bbrWfkM0X z)wSmVK28vtI5bYp)ZTy_*tyxw?)m7g{aHI3~h0MDAvn6zyPHCE6yy=|5> z$AI-DL5tDWmu&HF`RcVSymthSy!AQ~xw@S+jOmq)JjJ6Uci3HqMdk6Pngr3UvR&Ut;N0!F_hqrHj z^F6oU`JI1w`{5t{i?{FouFnLMUc``f?;&rU@~;P`f2BiX@E98ic(*NDSjWc_JgxiC z0?WD?2t&z|p1aqDY_R19)I(QTtv7hAw>ZetXmsE9!Ebe`<8#lIkw=!o0CAgxE;q@v zQ|6%7y5wf0G6yZCHo@GRBL_EqQ%ss?`K01F3sdUxZJ3LA< z4iB&4jg4SK^Y*vvlHAS>j`h+S966DFFWKe_Im8@lRdvtgVV3iywkQ6#9V_Zm^_Smm z6)U&sr3m$k5zGzLYq)KdzbuTesX5o%=rPG^Q33J)EPHr{B;>Wn8Tv& zhIz1-U$%~OW#_dKi5LH9L^ilnIzI}hZ3*{bIr-1~)~3j>I9fi#VH3ZrtY4oG&K!Zr zjWMe#d|4O0*q{2~Xx+4-V$%!1vDJR(U8&Cenn{}pQEctCD4y1pDnG=SbuPWH%DE?O z_>}x%je91>*ZON+qpnyubGnA-7k-SF&m>sr$^EDI0LJkoYUyJqm}X7FBt3}-zeSWU zc_(+K&a)0VhA)*Xfz{XGfp6xQA5$_IUfTzqSyR*WTs!n7m%Pu1EnbT>XIm=Z!nd9! zoj3P=?WTcP_QZ?7eDQ!yljibeK)&oC|BT6NLTs|;^uwO@-ue9U?GvB;)T94u+@JiD zZ?VxFvizD(AA3tAefYdklMv|ICF&sasqRpc zH2xsw!{rp(YXrvJOk0g11ZrZx8>!iYrvA7jE zztI^x(896iGO={3c>l6T=N#DIvejn<{I-1aeft}oZHGri@%7%G^EYcR-_<9d&}eiR z7=4%gpEC>)n>!b4VO#T~ZWsPyZ*yEnfIqJCWd&j6TF8CSgd5Uu86C=9n>21u#!u(vB&p%Um z$sZ*BVUqo%;(ZI(thZ&N)EIr%3*-I^YZUB`_F_Pb?dme}*ac6YDN`qpAoSMvo}@aSruLq=n@!&>aK znh)^&#Ghws_|Tj47C9*KcWc$ywm*Zn{!-hv#`}e-3Hy^Hso}>yu~#iT&YwjaH~-$T zSkQmcIx{gKqTRD~-7}aM)=fv8Y$LKzo7nL>lOrnLZ{uI~PTE~#bTs#@&vWDNUX6+ozv?=FvY0ee}=$%(#joH-;8+ySHlo zS#Y(@5#Gg5P;j))9&=Cvm*7DJt{aE~Zx#zVes2+M*f#sp*RmIum}&=pgqT2W*<9G0uji53dgdG3@!w`KBo{R1;&FGZ-u7&1GU>%EZ}cFZ`>2^<%f^ zp8NRi9q;(hZ-4BMeNI^W?MCAe`>aFtGX}w+GG$;A|#hQ92YZ*&!B=5kZ$I6ld# zg&XpolYDNfDjK6+CdF2rSI06c(OMA!YAjPEm#Ls zpBF%MtMV}Nyhg6P$Zr3{J)(|-->JcWo`;mR9(o1eJUmVeAnV3=_n?Wp=59hI_)DMhi0f=q}98Ron`v%cgm9EoSJMl3fvx54RNt{4CPFpzQd^r3+c zy0*@1LBjVli*lK9{Hnge*fH)Iox9Z2t}hZoo5yH-ud@~tS4U1V-qYS^6!b(S*eT>+ zF=xth;_n9|Vvv0i9mVYZuVQ}7slYQjmMzit5gknNfJd$;|8wt2-#&`pHU|Sf)V_7g z0q+|M*r#2J{SyFP&Jf}u9fwZ*1CjGdI#|!@imhGaQ{^_EJVP+K_+-zx94F}_wwhu- zdDWjfr0r)5m@ESha%y~2jaoIW*lR`HGGN(_A!n5LCAlykN}Qvb16}T!xmUU%J7t=>15}ypBRWayo2j(LnJi^F2p!L!Qv-Z%m>R$>nAbr`I{4BFuLLEL2SJg zy}-!)$_MrQLFs`*JAAO$cc`@qbzDRq)m;6pOxYvXv9w3XmB;5mM#ne5@$TD~zx?0p zgV0~Peed`EDhx1>kKuRYAbhra%rgLw`uOADcb}VK{G}Gpp|o| z)0YWdf;l`wCH~1(?RhYe51e1b(3l|O%6d1y(cr^X`g-F;0Gq+0oE6{t)^BnJo~#YB zQ#*E?XNf2BA@EJpZ7|FY032$sn2H0q_HlIDe~Ko}GrCrL>KPt)<%4u|J)29x+&!6f zqK4g8-#$YS284cYpc3pZsO6{9rT&Y#U4d zJa6%(_K-zZa}CNL@i_O!p7Aj?m&Hrico8#^xt5*~V>y>o6R)1fjrUaqWl@N3xBbpo zjk%w9dT#7GbnI!_V+}iw$(~8{OXLYY=MSgoz6-nN!AELDH ziHGsZDl-1kf6flek*my_Cpj0{eb07GJ)S&H9w3{12+sJB^R0Ww*QtkOE;6)>IcttT z$mT;+^sy)L(NQCID5I7X(zK!~J>I$Jhc|ntauKS1``;oP5aZ+za&-JMF3yboJm|Qv z&r~P>ursz|Mly+wJ03(^Xtx;7na=+I;`7fx`cH&@^20x|lA(G5=DN-p*bW4^77UzQ zjwpHjqf{0=Isl07Bxx38*GG}VXP>~G4{|olb!_$E>;k0(bIWq56!^h3xcniaNo9V? z(zJYdjfEs#{P1x*6Wic1mO0RE+p027QY9{l4W)Lh34H+&nd+c;Xnf-3xr6aDu4f(^yuoM!BJ+Gh^ZpA;}1m*u6=mSbHM$%VZRz4x40)eIZ-aI@hvWe$z&-h%8 zL@tq=Jz)Eg&%`(X^^f0v>;L+nZa?}XfARME?|ClrteYQvvbN++a33FV9OA}?IpvCK zgKcMx zyJyg63@WL>KyE?0+D`U_i-RzSIyh&oviHy(>{yPD-gpM%9I$IoVplkA7oF(wx@Yar zV%*|sTw?{G|;A zM{>`7U&o&686F>FYv)0~*^kb|E^BL9l~@_FP4=T+==Wqf&_-3=p<>QYdBUq{&j(NI zBWB_w?p_=6YOQ^=#_ZTKH`#!ns^9)eZ+lPBF8K5|h>jm%<4Z7qxYB$alN5ef zIz&!Pi*pG6V;pr(N{`N2K(~a@bOR;@uRKU`*3{0-j$*_ zb16{co&uL%vXT8(TgWBHlXJ1@y-HceYU64r#Z%+M&av#B@K{=xtbg(#=VI0njMWFI zey}jUfD}*8(_(?R@3E%TtYyxt;P*O-pL;tWuzatddkCe!cIR^t%*7|N|FW4n`=fD$ zH|_Lu5rLnII1c6+UQ{3ZK>_{M6}^caDl>k~8`{=EXLPAyUM5}fO2h52!kfBO{fU3= zPHv2j6i+#3%tu%L^I`sw2=Py@at}ZU;$36uW591Nv(Dnj|LjL%j7;L6^QwMFc3O^W z*0*O-_x{d3N}p>Y6(8V@f2tWDy}LnxY9niIV2h7#e1|WW$xG4)?0S9jlb?L_4?-XL z=tteg0LGgfr7nhPKyoD*8Jk)>#XKXIHe@a0Yp@Oba1sX3*|G4!5Ek01q!0`V2%Xf~ z@Ejh1K*va_f~{?+HwteC4rdaA16eiN`(TiTlP+VKwqB^irqwMw*i2no7^i&#DI0Zo zW-|>%-`JdC*tVTwtjxBMQF~U!)wAvg7s3?DNj(IhvPo6t=kcE$8u__aN6#VN=CO3QXKMw-?rh#0( zP3Nag*nt@5o3ehXl=CvYTp5#5+a>M;f7vA$c#vVOnIrDWi{wV^M5;EeZ)ymeE5^cc zd59TY<)>zSiA&cYxsdhS@j2`bIkqZ^TkbtwA81LUaLL&MFQjg2x3L}j*zO$meJ?RCa9}n3DP|L8&6vzk+M%&$Uq+Tu@%yK3 zsuNqdqK6WHQu?LP`svkt(9ZmrvfkNiYc95-@YKE=#^d3Ri6Wo1rg(pk|5=mdn$K+2 zoIRVac3a2J7<+)gK~dZtBk@TLNt)ooR`OqE9@NY?vee#B^Wmp2m_PDc*n55iHq@ zklm2pobSO;9XjwaZoJK5)+T!nce`KXx5dn#_{`bCw1~6MX8>_f4IlXP-vdM^W8q6o z!0Zp({x{A#2OZnopQxR))rk$s?VkXKuWJSac|hFy2Q?hS=D_%6f9(%)@tZM*8LNG> zc|IQcz9kVO8Jof7!J){5t=OUHPc9(i_2bOM9=!NS8U5lmKlbxZf1TT4rdWGqEIhm~ zeTV!>+*t$LCSQoRau)l>P7x;mb{A#FAoRG#u54|}S%E#jhCgx4JTYS}oXeIEepFI> zP5RR_-pl2bC19r~|1Ig=} zQ57o5_6FrL2VD91dN8tqKE&UN>#jbj&kUUFw{FH1C_r1Q>1NZm_UZZh4 z4|py*GyW2b8`Im3s`@NqRHojSld`JkC zGXal-eHebp-+1N*$piGOZ%;h&#O-yjd*b%^<2leu#gKg9CaQyG=B#l77oX(|>!fyl zXWTD!iFvRS&%|+rT{&l@gIrIJB}T2qs6sr@6+PozrXY2*UT(N<3|mUk&3es#8XS<> zbjbsViv17`kNr|}Mzi`wd-ulrzz?N;Y zwzHSAZ<90Lt1F(dgP!yiZ}lZ@ot?udF=oj4WIqoTi4}PT_O;%~K;qBCQ2b@QHzdoI zm+8S0yRlyk0X1#S<;I8JIUDpEi;+`Jf9bc4S-;ENb+66zw8zG@-KQR#_RBnqyJD}I zV9@2Y@~?TCb5T0I7Q-t!=WLtRb;#Ig!TifKJ4ltmA&4)Xd#xh zgO)ZuwuTck$BQx;bg^CPPy`l6;lX$GcCPtM$+^rI2<)+}&Bot2QEwT>=wsQj)=MLc zA3E(vSM@Qwd1`ChrFc4aWE-2rt@q(P4|Q##tMZPK);ay!y^`_hopWn^Re`h5I)2`e zet%e!{V|icS7!W4jCO3oT>oPuSfbziQFHchN*|upiK))fV_by3VrQ)UrOunByyL%Z z;M@46SxqTkv#-xsEFIuhqjs7%>R6w1K=a;X<7a5&g)jHF$a@M%1H1OX#@e#3)X`5l z`M@iTV~cg(KPl_8$i{|EY(w4$oHsn*i5I<68NJO>+ltNVFs{MRm}9usI`aK@%GsZ3 zCzh;ta`uct&l#Q*(Fp~MWI%vz!1%3KZ4Vyvn=>U?Dafiww?E{PQ>s0PpBNE=tZpZ`qGyl{oe@v_>aFY02r9sU?|qzpvI9I49^fvKq72Vc6fOGp1#M# z;|19Ao8LV|q)IO>{yt1SB|c$+zY7L)^^$}WxTPPNTx>Ip(ZvIYZzB9%dyQd}Z$$d-L@*2vQT)i5N7e4)dZSZMY{C)Qz??Rq{nkru zb6Rgy(>`OCjY64ZAMDJ zIbe|mLt>PIa`Z#L|NHOpzY%)ZJO9e<``++H$#rJejzQPneri;g>c#(-&Kr>rneIt^ z&Vj<1V`N3KK@%Y);3dY+8BIiY;%omb&#yWpz9y@RPWvc&;KA8ao5#6lywL$q^Dgld zw|O%^Y!`m?^TCvT#Rot?psAm^u{->|Nk%^39*M#8VA+&4^qAh~ULZilR2*g+87}Pg z`pvrer>n<@8tc~BIgY6Hil3T(;(!jMV$*)jm}7`en>R4aG6$b|wMUG5NTXar=zt$R zsy%EutsAxEBA>BRb?*ml`8sXJbs1gb)8M28AApPXt^i8)qOn!o#&uwU;!duRF{yB~ z_6H2Bj7`WG$A06_zeRKnPL2Pe#>to3ZegDBQgCN4(8hCOfr)y-JeO3nhgL~W1rvQF zAP-(_ho`*KI{`(83zoui=v=>#r`yC@s%77S^dT^dW+7IFUO) z07XskyRA#{EM3cjX!N>{QrF~v&l}&H<)dw2Yu254_6|D1k$;;!XGUOJcOdC%TiD6I z%NHK8<1zaQYu3ZH6;eZ3(|h?;Wy{+#!b&JLZeK!0fNbx4miKBjBXdb(8(Jat5Dq6^9J#uuR3;frf@GoS8OGYtefu@ z$S`QExZ9sDWQ|r{3`P4Q0W!8*2$fk68jY>b@V3)$=Izx_JI?tg{F{fBRb9yJH8WUIW z%&%aMEOWN6-0Ho*J|#cnqjgIrSSIFrJ^xDnjnEIh`3L>2mk%l_GP(g@0(c%s^g%$i zf%)LbA%ek#O2Sh?s9+xc^BZ@|uy6-iY@9I`Hr~FJ?{O0#z?F|^6A^L+4Uk+Jcu|4uW^mtg%3mdjMYnFJ-O&C1he9_}I(}zYr z2>PcJ!rc!h#;i8HIkY3=wU~8jIO5BWgXg9|zIj=na6C5OR%kA3$%795M=pMc>POcn zzU~9M{&tf>i6y$+wa$(aCx1|+J$XqXE`RXR5|VREa8^ z{n&i+Oyfc+pNlT0_{ED6^J~uY49G_F#Ag>ZKIjb(e&ky@a!|wL-}21{-Sn7crmp_X zj~p%Oh>cla;yG(vV!pVD4Kh|Ee%91>?E7Aa7I@4%gk|fJo@E!g<`w5FIw->rkK+cv zyNRLSY8MxOT!r?5%xjOUu^9?#;lko23Hy9h4`>dn{lrT zXBJ=X(bib@UtR~vV>vq>Mx!|);V~ufg zmRKmKRC?d7WnT@BvB=O5#^5eb_b~CrJag<}jsKWjXbm7l}oDE$-C$tquEYK5|CIXjI0QZF?lV zAwa3$bzZp^JIy`X!4o}MGhz|{&NH#TEdVuzb<8;y<%f4<+`i_eF=!20o9YKvkC9v|)+dmT7w>h)cxq zjAr!Yx_HjE3w~fb*hv6yU~S&~zHE|W9hz3Biv&qt+OdFDLr!0f6*J?CZ90rKDZAl| zCj_tBhn)4sxX1Ck@_sNu*8H2ok8kdcjp)h=e{Th3MUnmM`T{L1eUQ@lnR!-MFf%(r0J9{j#p%mGNOJgQ6i#)PT4O!>yw z-+lY_FaQ19+y2ada(n&jpA~m*T#$JtPULtWg8X1^yJKH(4pjd{(t9Fui7|YMfe(H# zayYYJb+ga93ZGv7z^cMc&%gGf+8?Af)-N)={@C?@N{Q~+*N`dkNgJ{cUgx8a^un2X z>!|SloqFfMQM{kw8(YBxudjoF2hr5#vrf%hXZYwdV;)iKMX;I^o;{C_tYNW7uX9K1 z;CjY9CzyY8a*uKA*BlhzDTzY~wdJWCNEu>$%s!y+#KZ`AJ4S&IR(zoWKDcZj zpNfU?(F4(1dW|7=TN-C3gJj6|u#=oAS(Prq6`iJS(rwMUX1eF7ZL;SK1jguZUZss> zWTDj_J2bn8?DxoUkMzTn$HX&ptc^d|4IgtQ{NrpO2DJM@%J3#Xv76Wj06IX?F^c^W zUDkozcORRK1&@I%ff$kJ@CQG%;vh=gB&%y>qbKprT10=uqht9s{vc~5CZk6o zj7zpM4-m|YFEMT#YP@R8qsKfHez)ANe^ZIJU+BnC>O+kwvdu5%PyaJtESzUNJNf_o z#0aoo6LbK<}ntM>ibAHXQ-gU7$VHXm?M z9sKCL`s96Q3}WIvwt_=EN8V8PxvtpLrmjC$?lnRU7b-@K!7|r1u71<-2aFr4+L+ej ziC){I&>lO?ueebZm)%zzVcOwbIP^C4yy#vrpWj>(`^GxArQCYKIp2#?4-Vq?*j@yq8G)eUU)sjW!r8t8`F$2-_7Pi z@|tj-H<~t~TbDI1i7}M6=S8ip(>&E1a?f+qGmCKPm4ljgcy`rxYAC*f$vqY32E+8K z!??{#&8$1oaTJq8kjf#UnwWW<>%lja_)SOD`HrJUQrQ4&9kZ^!IqMbQb2uQELr(lY z-1Om8`LJ@uc~L#&W&WYN^G~_wLk-*X!L9-|kMmIZhqr(I`|rE`-@p66-2Sb%{`9J8 z&BVn+mT?CK2lb|5-Lk>ic~WBsK5JCB=R?*yKWS}F8_UFPpV@Tci(^AU8@8c=6#x1m zE;sV-|Hwrb1(EW*h}R^Q*z}oA5gr@UbmBit@gR@E{ZU=%{QMsrLhcb*OEB zwl!n2l;0W49|6!l*Fz-#xEi3AXR@M_smAi4Ec5 z%T#}1IA0nr+*6`IXHq|$oP^!}A%o^`ZAq2wIB#TkT(%95&zPga+>8&K2!CR)GSpD) z?(@+&HD-3Pc%O(LO3oj+)wE{e3@@<-gOS7*dk3cgJUB39l_;)tP><^*P1-;zge!j0|mKlP>g|@Pik%F4k=yv*&s) z@YC}Qw`_sT(nxi>PPUBp8jqd73>C-BH5C|=~_Fd&ieG{AE6@=uNg60$yY)8@K6YoU_h zll+=mJVT5#HnSJqc_58l77OymQSpL6FQ-P@Hl{FO-|>;8sIMd(ahkCMiZNh6I;b<6 z_tu>oLz1TtE3h($e04Oj&M|9Db;YN4#-oc%`8TGS0JYyi?^x)Ko|1K|tZ$mv!^=o{ zUNv@jq1>uRr(TS)ei)8zjZYlOjkTdV=DbOt2RCa5yCrEWCf#s)h<99OIC+ldYI@as1G3CeH3IDdw60AF%k1sm9d$A8N8#c%tke&~SggKj>=@(;fC zf!puugU}EEJAd)^J+J?~Ksl3A;!5LVO}p)~a}r%KBj4}&Jf>Ik#Ic1dI7`-$cWTQ|y(Y3Q_p-K0L7?@t z!+MqT`g$zIleQzWX!RUzUbBxn)_9Z0+bzAj!K*T^?VD-FO+NKgQ}e#PH%7qP?()@Pqtp9GE-L*7zHLj2wL$ z&v}$DXL>eN@5(#NCijtFUyyn~=;07OV+W$yb1!=Eef!gK!_aHZsWRu?+DL)DkVg_%0BRvrun zi1=*%v%WJ2nNM>}V+)MFH|ZSjPlA}UZN(Bhv6VjL^^$@0#VY=43_-_Km{VhS@@E{b zp8)g-?S(1h$anxcurt^52bV~f-#k&nWd_$+?2M1T_;s2cU0`?LSHyKd-aS+X^AK{2 zJN&%Y;W3FDznM*4Iv1duAnl!)?ekj1@M(8!+5Dm31Ln(^^-)jT2L-y0WN0y;YA{Cv z-6Tj33BKXyq0<{g6X40i%6!mpX)ctqq4I$u8w>4VUYL&Jb)L1xcyD^Ak8Lj*cq!vE zlyP*W#@NZQ?N^I$*8u7*Vjc>f`_JuF} zo!fig``2!7e)F$+4xQTv;f7!3%oo~>HTP^u6%PTunNs^9mTB9K{3;Wx9%3h1C4x0> zv*Kg;l%KeQfe(&(aG!NIp5Vg{x#C|1oe!wi;WE12kc@olzc0%-wtQ2W`Q{xrA9Ms} zY`}+2#wqZ*eU}f!#JG?KoBc--#D@{EXYGrB$+!%saOzDc6>+2#ort4 zaK*Mo{Ltrzz}b`cIcyt5&oZ?XdFHL(cC)AQ>pjA#V)A?`de`}_5j4V5oA+mX&mQN2 z{5KBuq59Dpk;X5D*ivtO;U#|5DbSfm{Ry1`ieQ0npM!~gbVi4L7e@8)a;*V+ane?- z#}YFD#b@7Bz)Jkdqs1`18p0fNu_s&DBo9=Wvu<5ngwto5sWKU_!rH9A!D|8AYpz20 zv?f)jpYe-b7c3+`);l$$$z5_dxy)J7eSvInXx+SaDS1eaZO0Y+v!++Olzpbt4-!`< ziCE6X*k`_k84bV}S`FbEf55{UiO)H4*iL?+bF`|W?fmTrA=X6(s>?Wsk0#hwoaR{< z9K~I^=6B*W_d>?$4^PiaD9=QCQ;QtK!@u~@I&0NjkNseyZ5}X2!17Sfx#g#*HmbAF z?*6hh6DYRsl#$Upb|!D6j~sRkyszcweBj#qN7$@Vwy}q9bm&!`)abBo6|ap7HV`Jq zyeDQqe)-pb{n0-NJ@wQFW`VLur!bgOU&K}bN~=8%_*3x&p$kI^@bGl3<8_Xkv->K{ z;pkjMvBU65#S`qs6{d`Ha4;Ue@+PsOuj6_;rwr z<)qk5O~buI<>y0q;P)Z&}O1H-acHSC$>YyVWqB9?LC?`fr^pb=O;QjPsZ1yY@aM; z*=_U6TOVMCzaz!zoG30)bnpB<$-eu6HXmp@kDcyG=jIUO)3WVC%y>#{?KS5QP1w%p zj!tfB(r+8t1HOki=Fx`__E)7in5)hDRcb$Dku9aY^)0zk*zuN7blC@P=-iv+1Cp
    +
    +

    This page is on a release branch, and hence possibly out of date. See the latest version.

    +
    +
    This document covers all changes in PX4 v1.16.0 since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)). -::: warning -These notes include only changes merged in 2023 and later—no commits from before 2023 are listed. +::: info +These notes include only changes merged in 2023 and later — commits before 2023 are not listed. ::: ## Read Before Upgrading @@ -45,7 +56,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Common -- [PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936): Optical flow: add scale factor parameter +- [Optical flow scaling factor - SENS_FLOW_SCALE](../sensor/optical_flow.md#scale-factor). ([PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936)). - [PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813): Reintroduce optional parameter versioning mechanism for airframe maintainers - [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). diff --git a/docs/en/releases/main.md b/docs/en/releases/main.md index b0cc688741..5250b1551c 100644 --- a/docs/en/releases/main.md +++ b/docs/en/releases/main.md @@ -9,15 +9,15 @@ const { site } = useData();
    -

    This page is on a release bramch, and hence probably out of date. See the latest version.

    +

    This page is on a release branch, and hence probably out of date. See the latest version.

    -This contains changes to PX4 `main` branch since the last major release ([PX v1.15](../releases/1.15.md)). +This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)). ::: warning -The PX4 v1.15 release is in beta testing, pending release. -Update these notes with features that are going to be in `main` but not the PX4 v1.15 release. +The PX4 v1.16 release is in beta testing, pending release. +Update these notes with features that are going to be in `main` but not the PX4 v1.16 release. ::: ## Read Before Upgrading @@ -40,22 +40,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Common -- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). - - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. - - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). -- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. - The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). -- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. - This makes log decryption much easier, as there is no need to download or identify a separate key file. - ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). -- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. - Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. - This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. - ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). -- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) -- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. - This typically reduces false warnings due to magnetometer inconsistencies. - ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). +- TBD ### Control @@ -71,26 +56,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Simulation -- [SIH]: - - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. - ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). - - SIH now supports the standard VTOL airframe - ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). -- [Gazebo]: - - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. - The default installer scripts (used for CI) and documentation have been updated. - This is required because Garden end-of-life is Nov 2024. - ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) - - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). - - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). - - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). - - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). - - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). - - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). - - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) - - [Moving platform simulation](../sim_gazebo_gz/worlds#moving-platform) ([PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471)) +- TBD ### Ethernet @@ -98,7 +64,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 -- **[Feature]** [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113)) +- TBD ### MAVLink @@ -106,8 +72,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Multi-Rotor -- Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) -- Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507) +- TBD ### VTOL @@ -115,29 +80,11 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Fixed-wing -- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) +- TBD ### Rover -This release contains a major rework for the rover support in PX4: - -- Complete restructure of the [rover related documentation](../frames_rover/index.md). -- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). -- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): - - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). -- New module dedicated to [differential rovers](../frames_rover/differential.md): - - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). -- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): - - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). -- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). - This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): - - Generic Differential Rover `50000`. - - Generic Ackermann Rover `51000`. - - Axial SCX10 2 Trail Honcho `51001`. - - Generic Mecanum Rover `52000`. -- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. -- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). -- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. +- TBD ### ROS 2 From c3946ff56f587b9e55a74f26cbc648e251c2b29f Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 4 Jun 2025 12:25:09 +1000 Subject: [PATCH 098/130] Add FW release note to Main release notes --- docs/en/releases/main.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/en/releases/main.md b/docs/en/releases/main.md index 5250b1551c..47e4c6a1bc 100644 --- a/docs/en/releases/main.md +++ b/docs/en/releases/main.md @@ -16,7 +16,7 @@ const { site } = useData(); This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)). ::: warning -The PX4 v1.16 release is in beta testing, pending release. +PX4 v1.16 is in candidate-release testing, pending release. Update these notes with features that are going to be in `main` but not the PX4 v1.16 release. ::: @@ -64,7 +64,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 -- TBD +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). ### MAVLink From 3a4dc784eb817d0b67ba423fc3fbaba7fe827b7e Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 4 Jun 2025 12:26:35 +1000 Subject: [PATCH 099/130] Fix up badges refering to main/v116 to just be 116 --- docs/en/dev_log/log_encryption.md | 2 +- docs/en/flight_controller/kakuteh7-wing.md | 10 +++++----- docs/en/flight_modes_rover/ackermann.md | 2 +- docs/en/flight_modes_rover/differential.md | 2 +- docs/en/flight_modes_rover/mecanum.md | 2 +- docs/en/frames_rover/ackermann.md | 2 +- docs/en/frames_rover/differential.md | 2 +- docs/en/frames_rover/mecanum.md | 2 +- docs/en/middleware/uorb.md | 4 ++-- docs/en/ros2/px4_ros2_control_interface.md | 6 +++--- docs/en/ros2/px4_ros2_msg_translation_node.md | 4 ++-- docs/en/ros2/user_guide.md | 4 ++-- docs/en/sim_gazebo_gz/worlds.md | 2 +- 13 files changed, 22 insertions(+), 22 deletions(-) diff --git a/docs/en/dev_log/log_encryption.md b/docs/en/dev_log/log_encryption.md index a2d3122390..bc93913d32 100644 --- a/docs/en/dev_log/log_encryption.md +++ b/docs/en/dev_log/log_encryption.md @@ -12,7 +12,7 @@ To use it you will need to build firmware with this feature enabled and then upl ::: ::: tip -Log encryption was has been improved in PX4 main (v1.16+) to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). +Log encryption was has been improved in PX4 v1.16 to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). In earlier versions the encrypted symmetric key was stored in a separate file. For more information see the [Log Encryption (PX4 v1.15)](https://docs.px4.io/v1.15/en/dev_log/log_encryption.html). diff --git a/docs/en/flight_controller/kakuteh7-wing.md b/docs/en/flight_controller/kakuteh7-wing.md index 5d9a29cea6..775eca078b 100644 --- a/docs/en/flight_controller/kakuteh7-wing.md +++ b/docs/en/flight_controller/kakuteh7-wing.md @@ -1,4 +1,6 @@ -# Holybro Kakute H7 V2 +# Holybro Kakute H743-Wing + + :::warning PX4 does not manufacture this (or any) autopilot. @@ -33,9 +35,7 @@ The board can be bought from one of the following shops (for example): | Buz-, Buz+ | Piezo buzzer | | | M1 to M14 | Motor signal outputs | | - - -## PX4 Bootloader Update +## PX4 Bootloader Update {#bootloader} The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki). Before the PX4 firmware can be installed, the _PX4 bootloader_ must be flashed. @@ -52,7 +52,7 @@ make holybro_kakuteh7-wing_default ## Installing PX4 Firmware ::: info -KakuteH7-wing is supported with PX4 master & PX4 v1.16 or newer.. +KakuteH7-wing is supported in PX4 v1.16 or newer. Prior to that release you will need to manually build and install the firmware. ::: diff --git a/docs/en/flight_modes_rover/ackermann.md b/docs/en/flight_modes_rover/ackermann.md index 4115252e4e..d19f24eb3e 100644 --- a/docs/en/flight_modes_rover/ackermann.md +++ b/docs/en/flight_modes_rover/ackermann.md @@ -135,7 +135,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | Command | Description | | ------------------- | ------------------------------------------------------------ | ------------------------------------------------- | diff --git a/docs/en/flight_modes_rover/differential.md b/docs/en/flight_modes_rover/differential.md index 8917ad3924..78548e54ef 100644 --- a/docs/en/flight_modes_rover/differential.md +++ b/docs/en/flight_modes_rover/differential.md @@ -114,7 +114,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | Command | Description | | ------------------- | ------------------------------------------------------------------------------ | ---------------------------------------------------------------- | diff --git a/docs/en/flight_modes_rover/mecanum.md b/docs/en/flight_modes_rover/mecanum.md index 3286d42328..fc5783f3dc 100644 --- a/docs/en/flight_modes_rover/mecanum.md +++ b/docs/en/flight_modes_rover/mecanum.md @@ -139,7 +139,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | Command | Description | | ------------------- | ------------------------------------------------------------------------------ | ---------------------------------------------------------------- | diff --git a/docs/en/frames_rover/ackermann.md b/docs/en/frames_rover/ackermann.md index f3f4497a60..8ef32c8496 100644 --- a/docs/en/frames_rover/ackermann.md +++ b/docs/en/frames_rover/ackermann.md @@ -1,6 +1,6 @@ # Ackermann Rovers - + An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates. This kind of steering is used on most commercial vehicles, including cars, trucks etc. diff --git a/docs/en/frames_rover/differential.md b/docs/en/frames_rover/differential.md index a74fbd1d50..95ffe04993 100644 --- a/docs/en/frames_rover/differential.md +++ b/docs/en/frames_rover/differential.md @@ -1,6 +1,6 @@ # Differential Rovers - + A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate. Forward motion is achieved by driving both wheels at the same speed in the same direction. diff --git a/docs/en/frames_rover/mecanum.md b/docs/en/frames_rover/mecanum.md index 7d9a249156..548e7bcf4c 100644 --- a/docs/en/frames_rover/mecanum.md +++ b/docs/en/frames_rover/mecanum.md @@ -1,6 +1,6 @@ # Mecanum Rovers - + A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first. Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place. diff --git a/docs/en/middleware/uorb.md b/docs/en/middleware/uorb.md index e5f61f2567..a164abadae 100644 --- a/docs/en/middleware/uorb.md +++ b/docs/en/middleware/uorb.md @@ -116,9 +116,9 @@ As there are external tools using uORB messages from log files, such as [Flight ## Message Versioning - + -Optional message versioning was introduced in the `main` branch (planned for PX4 v1.16+) to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. +Optional message versioning was introduced PX4 v1.16 to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. Versioned messages are designed to remain more stable over time compared to their non-versioned counterparts, as they are intended to be used across multiple releases of PX4 and external systems, ensuring greater compatibility over longer periods. Versioned messages include an additional field `uint32 MESSAGE_VERSION = x`, where `x` corresponds to the current version of the message. diff --git a/docs/en/ros2/px4_ros2_control_interface.md b/docs/en/ros2/px4_ros2_control_interface.md index 8979861a7d..e7e3151c6c 100644 --- a/docs/en/ros2/px4_ros2_control_interface.md +++ b/docs/en/ros2/px4_ros2_control_interface.md @@ -341,7 +341,7 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: - [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -403,7 +403,7 @@ _goto_setpoint->update( #### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) - + ::: info This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. @@ -545,7 +545,7 @@ If you want to control an actuator that does not control the vehicle's motion, b ### Controlling a VTOL - + To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: diff --git a/docs/en/ros2/px4_ros2_msg_translation_node.md b/docs/en/ros2/px4_ros2_msg_translation_node.md index a221d3fcb4..f9dab8a42a 100644 --- a/docs/en/ros2/px4_ros2_msg_translation_node.md +++ b/docs/en/ros2/px4_ros2_msg_translation_node.md @@ -1,6 +1,6 @@ # PX4 ROS 2 Message Translation Node - + The message translation node allows ROS 2 applications that were compiled against different versions of the PX4 messages to interwork with newer versions of PX4, and vice versa, without having to change either the application or the PX4 side. @@ -207,7 +207,7 @@ Message translations can be either _direct_ or _generic_. ### File Structure -Starting from PX4 v1.16 (main), the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: +Starting from PX4 v1.16, the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: ``` PX4-Autopilot diff --git a/docs/en/ros2/user_guide.md b/docs/en/ros2/user_guide.md index 04694a26ae..b13ba10b02 100644 --- a/docs/en/ros2/user_guide.md +++ b/docs/en/ros2/user_guide.md @@ -34,7 +34,7 @@ The generator uses the uORB message definitions in the source tree: [PX4-Autopil ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases). -Starting from PX4 v1.16 (main) in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. +Starting from PX4 v1.16, in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. This requires the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to be running to ensure that messages can be converted and exchanged correctly. Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. @@ -367,7 +367,7 @@ accelerometer_integral_dt: 4739 #### (Optional) Starting the Translation Node - + This example is built with PX4 and ROS2 versions that use the same message definitions. If you were to use incompatible [message versions](../middleware/uorb.md#message-versioning) you would need to install and run the [Message Translation Node](./px4_ros2_msg_translation_node.md) as well, before running the example: diff --git a/docs/en/sim_gazebo_gz/worlds.md b/docs/en/sim_gazebo_gz/worlds.md index ef2d4206d0..7f0c4821c4 100644 --- a/docs/en/sim_gazebo_gz/worlds.md +++ b/docs/en/sim_gazebo_gz/worlds.md @@ -75,7 +75,7 @@ World with walls that is designed for testing [collision prevention](../computer ## Moving Platform - + [Empty world](#default) with the addition of a flat moving platform, to simulate drone operations from moving vehicles like ships or trucks. The platform is controlled by a plugin which is included in the world. The platform is at a height of 2m, so place the vehicle on it with: From 09d734955da6403b08233454f0886a2dc4207a02 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 4 Jun 2025 12:34:18 +1000 Subject: [PATCH 100/130] Add ignore errors --- docs/_link_checker_sc/ignore_errors.json | 54 ++++++++++++++++++++++++ 1 file changed, 54 insertions(+) diff --git a/docs/_link_checker_sc/ignore_errors.json b/docs/_link_checker_sc/ignore_errors.json index 3e06929dec..2914c56f27 100644 --- a/docs/_link_checker_sc/ignore_errors.json +++ b/docs/_link_checker_sc/ignore_errors.json @@ -956,5 +956,59 @@ "type": "PageNotLinkedInternally", "fileRelativeToRoot": "en\\config\\_autotune.md", "hideReason": "Page is intended to be an orphan" + }, + { + "type": "UrlToLocalSite", + "fileRelativeToRoot": "en\\computer_vision\\path_planning_interface.md", + "link": { + "url": "https://docs.px4.io/v1.14/en/computer_vision/path_planning_interface.html", + "text": "PX4 v1.14 docs" + }, + "hideReason": "Intended" + }, + { + "type": "UrlToLocalSite", + "fileRelativeToRoot": "en\\dev_log\\log_encryption.md", + "link": { + "url": "https://docs.px4.io/v1.15/en/dev_log/log_encryption.html", + "text": "Log Encryption (PX4 v1.15)" + }, + "hideReason": "Intended" + }, + { + "type": "UrlToLocalSite", + "fileRelativeToRoot": "en\\releases\\1.16.md", + "link": { + "url": "https://docs.px4.io/main/en/releases/main.html", + "text": "See the latest version" + }, + "hideReason": "intended" + }, + { + "type": "UrlToLocalSite", + "fileRelativeToRoot": "en\\releases\\main.md", + "link": { + "url": "https://docs.px4.io/main/en/releases/main.html", + "text": "See the latest version" + }, + "hideReason": "intended" + }, + { + "type": "UrlToLocalSite", + "fileRelativeToRoot": "en\\robotics\\index.md", + "link": { + "url": "https://docs.px4.io/v1.12/en/robotics/dronekit.html", + "text": "PX4 v1.12 > DroneKit" + }, + "hideReason": "Intended" + }, + { + "type": "UrlToLocalSite", + "fileRelativeToRoot": "en\\ros2\\user_guide.md", + "link": { + "url": "https://docs.px4.io/v1.13/en/ros/ros2_comm.html", + "text": "PX4 v1.13 Docs" + }, + "hideReason": "intended" } ] \ No newline at end of file From e487d59521ae30c2dc86ec95b0de88f356f47d27 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 26 May 2025 12:24:16 +0200 Subject: [PATCH 101/130] Vehicle_odometry: protect angular_velocity field against aliasing Accumulate delta-angles between each publication to get the correct angular velocity between two attitudes --- src/modules/ekf2/EKF/estimator_interface.h | 1 + .../EKF/output_predictor/output_predictor.cpp | 26 +++++++++++++++++-- .../EKF/output_predictor/output_predictor.h | 4 +++ src/modules/ekf2/EKF2.cpp | 4 +-- 4 files changed, 30 insertions(+), 5 deletions(-) diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 18ffeef55f..0a8272a929 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -247,6 +247,7 @@ public: int getNumberOfActiveVerticalVelocityAidingSources() const; const matrix::Quatf &getQuaternion() const { return _output_predictor.getQuaternion(); } + Vector3f getAngularVelocityAndResetAccumulator() { return _output_predictor.getAngularVelocityAndResetAccumulator(); } float getUnaidedYaw() const { return _output_predictor.getUnaidedYaw(); } Vector3f getVelocity() const { return _output_predictor.getVelocity(); } diff --git a/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp index c165303574..2c65279049 100644 --- a/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp @@ -113,6 +113,9 @@ void OutputPredictor::reset() _delta_vel_sum.setZero(); _delta_vel_dt = 0.f; + _delta_angle_sum.setIdentity(); + _delta_angle_sum_dt = 0.f; + _delta_angle_corr.setZero(); _vel_err_integ.setZero(); @@ -247,13 +250,18 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector // update auxiliary yaw estimate // rotate the state quternion by the delta quaternion only corrected for bias without EKF corrections - const Vector3f delta_angle_unaided = delta_angle - delta_angle_bias_scaled; + const Quatf delta_quat_unaided = Quatf(AxisAnglef(delta_angle - delta_angle_bias_scaled)); const float yaw_state = Eulerf(quat_nominal_before_update).psi(); - const Quatf quat_unaided = quat_nominal_before_update * Quatf(AxisAnglef(delta_angle_unaided)); + const Quatf quat_unaided = quat_nominal_before_update * delta_quat_unaided; const float yaw_without_aiding = Eulerf(quat_unaided).psi(); // Yaw before delta quaternion applied and yaw after. The difference is the delta yaw. Accumulate it. const float unaided_delta_yaw = yaw_without_aiding - yaw_state; _unaided_yaw = matrix::wrap_pi(_unaided_yaw + unaided_delta_yaw); + + // angular velocity downsampling + _delta_angle_sum *= delta_quat_unaided; + _delta_angle_sum.normalize(); + _delta_angle_sum_dt += delta_angle_dt; } void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, @@ -412,3 +420,17 @@ void OutputPredictor::resetVelocityDerivativeAccumulation() _delta_vel_dt = 0.f; _delta_vel_sum.setZero(); } + +Vector3f OutputPredictor::getAngularVelocityAndResetAccumulator() +{ + Vector3f angular_velocity; + + if (_delta_angle_sum_dt > FLT_EPSILON) { + angular_velocity = AxisAnglef(_delta_angle_sum) / _delta_angle_sum_dt; + } + + _delta_angle_sum.setIdentity(); + _delta_angle_sum_dt = 0.f; + + return angular_velocity; +} diff --git a/src/modules/ekf2/EKF/output_predictor/output_predictor.h b/src/modules/ekf2/EKF/output_predictor/output_predictor.h index e90bdf9481..f9643b3ec2 100644 --- a/src/modules/ekf2/EKF/output_predictor/output_predictor.h +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.h @@ -95,6 +95,8 @@ public: const matrix::Quatf &getQuaternion() const { return _output_new.quat_nominal; } + matrix::Vector3f getAngularVelocityAndResetAccumulator(); + // get a yaw value solely based on bias-removed gyro integration float getUnaidedYaw() const { return _unaided_yaw; } @@ -192,6 +194,8 @@ private: matrix::Vector3f _imu_pos_body{}; ///< xyz position of IMU in body frame (m) + matrix::Quatf _delta_angle_sum{}; + float _delta_angle_sum_dt{0.f}; float _unaided_yaw{}; // output complementary filter tuning diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 974e748719..01bda5ead8 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1676,9 +1676,7 @@ void EKF2::PublishOdometry(const hrt_abstime ×tamp, const imuSample &imu_sa _ekf.getVelocity().copyTo(odom.velocity); // angular_velocity - const Vector3f rates{imu_sample.delta_ang / imu_sample.delta_ang_dt}; - const Vector3f angular_velocity = rates - _ekf.getGyroBias(); - angular_velocity.copyTo(odom.angular_velocity); + _ekf.getAngularVelocityAndResetAccumulator().copyTo(odom.angular_velocity); // velocity covariances _ekf.getVelocityVariance().copyTo(odom.velocity_variance); From 8e399ed78e3a7660cfd8cd9f27531eee1cfb53af Mon Sep 17 00:00:00 2001 From: Seungbin Lee <61672539+svin3@users.noreply.github.com> Date: Mon, 2 Jun 2025 10:52:03 +0900 Subject: [PATCH 102/130] Update jfi_telemetry.md Change the range from 500 meters to 1000 meters. --- docs/en/telemetry/jfi_telemetry.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/en/telemetry/jfi_telemetry.md b/docs/en/telemetry/jfi_telemetry.md index 553357f5fd..a6e7073379 100644 --- a/docs/en/telemetry/jfi_telemetry.md +++ b/docs/en/telemetry/jfi_telemetry.md @@ -20,7 +20,7 @@ Operating in the 2.4GHz frequency band, it allows unrestricted global use withou - **Frequency Band:** 2.4GHz - **Speed:** Up to 11 Mbps (adjustable) -- **Range:** Up to 500 meters (varies upon environments) +- **Range:** Up to 1000 meters (varies upon environments) - **Payload Capacity:** Up to 1024 bytes ### Network Schemes From 7e055656b0e7c20705f02c576559b1783992633b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 23 May 2025 15:02:45 +0200 Subject: [PATCH 103/130] uavcan esc: translate temperature field from Kelvin to Celsius --- src/drivers/uavcan/actuators/esc.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/uavcan/actuators/esc.cpp b/src/drivers/uavcan/actuators/esc.cpp index de1f5ad2a9..3eb07e08d5 100644 --- a/src/drivers/uavcan/actuators/esc.cpp +++ b/src/drivers/uavcan/actuators/esc.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #define MOTOR_BIT(x) (1<<(x)) @@ -147,7 +148,7 @@ UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure Date: Sun, 4 May 2025 12:25:52 -0700 Subject: [PATCH 104/130] Fix reporting of connected battery --- src/modules/commander/esc_calibration.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/esc_calibration.cpp b/src/modules/commander/esc_calibration.cpp index 3e78578dff..e96b3b2a32 100644 --- a/src/modules/commander/esc_calibration.cpp +++ b/src/modules/commander/esc_calibration.cpp @@ -63,14 +63,14 @@ bool check_battery_disconnected(orb_advert_t *mavlink_log_pub) const bool recent_battery_measurement = hrt_absolute_time() < (battery_status_sub.get().timestamp + 1_s); - if (!recent_battery_measurement) { + if (recent_battery_measurement) { // We have to send this message for now because "battery unavailable" gets ignored by QGC calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Disconnect battery and try again"); return false; } // Make sure battery is reported to be disconnected - if (recent_battery_measurement && !battery_status_sub.get().connected) { + if (!recent_battery_measurement && !battery_status_sub.get().connected) { return true; } From 84cb748080b41a888dd0c84966932f16f26ccba3 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 14 May 2025 17:40:51 +0200 Subject: [PATCH 105/130] esc_calibration: simplify the logic and consider battery only connected if there's no message timeout and the connected flag is set --- src/modules/commander/esc_calibration.cpp | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/src/modules/commander/esc_calibration.cpp b/src/modules/commander/esc_calibration.cpp index e96b3b2a32..4977ad5c0d 100644 --- a/src/modules/commander/esc_calibration.cpp +++ b/src/modules/commander/esc_calibration.cpp @@ -63,19 +63,13 @@ bool check_battery_disconnected(orb_advert_t *mavlink_log_pub) const bool recent_battery_measurement = hrt_absolute_time() < (battery_status_sub.get().timestamp + 1_s); - if (recent_battery_measurement) { - // We have to send this message for now because "battery unavailable" gets ignored by QGC + if (recent_battery_measurement && battery_status_sub.get().connected) { calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Disconnect battery and try again"); return false; - } - // Make sure battery is reported to be disconnected - if (!recent_battery_measurement && !battery_status_sub.get().connected) { + } else { return true; } - - calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Disconnect battery and try again"); - return false; } static void set_motor_actuators(uORB::Publication &publisher, float value, bool release_control) From 82c2e6c15995b125158dd8a149e82b352d6aab06 Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Tue, 27 May 2025 18:19:56 -0700 Subject: [PATCH 106/130] 3dr_ctrl-zero-h7-oem-revg: Adding missing module which prevented the USB interface to start --- boards/3dr/ctrl-zero-h7-oem-revg/default.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board index 326bb98a93..bbb20fd252 100644 --- a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board +++ b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y From 6095fc710c244cb2af94ea03b94e15fd4161e48b Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 5 Jun 2025 03:07:44 +1000 Subject: [PATCH 107/130] Update rcS - fix trivial typo (#24963) --- ROMFS/px4fmu_common/init.d/rcS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index f182d31eff..a22cb9c734 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -39,7 +39,7 @@ set VEHICLE_TYPE none # Airframe parameter versioning # Value set to 1 by default but can optionally be overridden in the airframe configuration startup script. # Airframe maintainers can ensure a reset to the airframe defaults during an update by increasing by one. -# e.g. add line "set PARAM_DEFAULTS_VER 2" in your airframe file to build the first update that enfoces a reset. +# e.g. add line "set PARAM_DEFAULTS_VER 2" in your airframe file to build the first update that enforces a reset. set PARAM_DEFAULTS_VER 1 # From 6d35ad5d9b67dd4fb4e6e3507f945fc9c64b455b Mon Sep 17 00:00:00 2001 From: Niklas Hauser <121870655+niklaut@users.noreply.github.com> Date: Wed, 4 Jun 2025 19:20:34 +0200 Subject: [PATCH 108/130] [uavcan] Fix safety state not getting published (#24972) --- src/drivers/uavcan/uavcan_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/uavcan/uavcan_main.cpp b/src/drivers/uavcan/uavcan_main.cpp index ad39a943a7..05fd6201d2 100644 --- a/src/drivers/uavcan/uavcan_main.cpp +++ b/src/drivers/uavcan/uavcan_main.cpp @@ -546,7 +546,7 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events) #endif -#if defined(CONFIG_UAVCAN_SAFETY_CONTROLLER) +#if defined(CONFIG_UAVCAN_SAFETY_STATE_CONTROLLER) ret = _safety_state_controller.init(); if (ret < 0) { From d1e7f019944a70b10ef1fceef43e4bb2e4e7c6b2 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 29 May 2025 11:28:01 +1000 Subject: [PATCH 109/130] Docs: add skeleton topic for indicating protocol support --- docs/en/SUMMARY.md | 5 +- docs/en/mavlink/index.md | 88 +++++++++++++++++++++++++++++++++++ docs/en/mavlink/protocols.md | 53 +++++++++++++++++++++ docs/en/middleware/mavlink.md | 88 +---------------------------------- 4 files changed, 145 insertions(+), 89 deletions(-) create mode 100644 docs/en/mavlink/index.md create mode 100644 docs/en/mavlink/protocols.md diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index aa6dcbc6d0..a94d3c15ea 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -722,12 +722,13 @@ - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - - [MAVLink Messaging](middleware/mavlink.md) + - [MAVLink Messaging](mavlink/index.md) - [Adding Messages](mavlink/adding_messages.md) - [Streaming Messages](mavlink/streaming_messages.md) - [Receiving Messages](mavlink/receiving_messages.md) - [Custom MAVLink Messages](mavlink/custom_messages.md) - - [Standard Modes Protocol](mavlink/standard_modes.md) + - [Protocols/Microservices](mavlink/protocols.md) + - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [Modules & Commands](modules/modules_main.md) - [Autotune](modules/modules_autotune.md) diff --git a/docs/en/mavlink/index.md b/docs/en/mavlink/index.md new file mode 100644 index 0000000000..8b81cbe595 --- /dev/null +++ b/docs/en/mavlink/index.md @@ -0,0 +1,88 @@ +# MAVLink Messaging + +[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. + +PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. + +This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices. +It also links instructions for how you can add PX4 support for: + +- [Adding Standard Messages](../mavlink/adding_messages.md) +- [Streaming MAVLink messages](../mavlink/streaming_messages.md) +- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) +- [Custom MAVLink Messages](../mavlink/custom_messages.md) +- [Protocols/Microservices](../mavlink/protocols.md) + +::: info +We do not yet cover _command_ handling and sending, or how to implement your own microservices. +::: + +## MAVLink Overview + +MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links. + +_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. +They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. +Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. + +The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement. +Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. +The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. +The command is resent automatically if no acknowledgment is received. +Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. + +[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages. +They are used to communicate information that cannot be sent in a single message, and to deliver features such as reliable communication. +The command protocol described above is one such service. +Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html). + +MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). +The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages. +Note that most generated libraries do not create code to implement microservices. + +The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): + +- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. + The definitions move to `common.xml` if accepted following testing. +- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. + These are supported by many flight stacks, ground stations, and MAVLink peripherals. + Flight stacks that use these definitions are more likely to interoperate. +- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. + They are present on the vast majority of flight stacks and implemented in the same way. +- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. + +The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. + +The protocol relies on each end of the communication having a shared definition of what messages are being sent. +What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition. + + + +## PX4 and MAVLink + +PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. +In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. + +::: info +To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). +During development you can use definitions in `development.xml`. +You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. +::: + +PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). +This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). + +The build toolchain generates the MAVLink 2 C header files at build time. +The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: + +- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). + You can change this to any other definition file, but the file must include `common.xml`. +- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). + +The files are generated into the build directory: `/build//mavlink/`. diff --git a/docs/en/mavlink/protocols.md b/docs/en/mavlink/protocols.md new file mode 100644 index 0000000000..316c527469 --- /dev/null +++ b/docs/en/mavlink/protocols.md @@ -0,0 +1,53 @@ +# MAVLink Microservices (Protocols) + +MAVLink "microservices" are a protocols that use multiple messages exchanged between components to communicate more complicated information. +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) provides an efficient mechanism for packaging a command in a (particular) message and receiving acknowledgement of the command in another message. + +MAVLink microservices are documented the [MAVLink Guide](https://mavlink.io/en/services/) (this is not exhaustive: not all messages are grouped into protocols and not all protocols are documented). + +This section lists the services known to be supported/not supported by PX4 in this version. + +## Supported Microservices + +These services are known to be supported in some form: + +- [Battery Protocol](https://mavlink.io/en/services/battery.html) + - [BATTERY_STATUS](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) and [BATTERY_INFO](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) are streamed. +- Camera Protocols + - [Camera Protocol v2](https://mavlink.io/en/services/camera.html) + - [Camera Definition](https://mavlink.io/en/services/camera_def.html) + - [Camera Protocol v1 (Simple Trigger Protocol)](https://mavlink.io/en/services/camera_v1.html) +- [Command Protocol](https://mavlink.io/en/services/command.html) +- [Component Metadata Protocol (WIP)](https://mavlink.io/en/services/component_information.html) +- [Events Interface (WIP)](https://mavlink.io/en/services/events.html) +- [File Transfer Protocol (FTP)](https://mavlink.io/en/services/ftp.html) +- Gimbal Protocols + - [Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html) + - Can be enabled by [Gimbal Configuration](../advanced/gimbal_control.md#mavlink-gimbal-mnt-mode-out-mavlink) + - PX4 an act as a MAVLink Gimbal for one FC-connected Gimbal + - [Gimbal Protocol v1 (superseded)](https://mavlink.io/en/services/gimbal.html) +- [Heartbeat/Connection Protocol](https://mavlink.io/en/services/heartbeat.html) +- [High Latency Protocol](https://mavlink.io/en/services/high_latency.html) — PX4 streams [HIGH_LATENCY2](https://mavlink.io/en/messages/common.html#HIGH_LATENCY2) +- [Image Transmission Protocol](https://mavlink.io/en/services/image_transmission.html) +- [Landing Target Protocol](https://mavlink.io/en/services/landing_target.html) +- [Manual Control (Joystick) Protocol](https://mavlink.io/en/services/manual_control.html) +- [MAVLink Id Assignment (sysid, compid)](https://mavlink.io/en/services/mavlink_id_assignment.html) +- [Mission Protocol](https://mavlink.io/en/services/mission.html) +- [Offboard Control Protocol](https://mavlink.io/en/services/offboard_control.html) +- [Remote ID](../peripherals/remote_id.md) ([Open Drone ID Protocol](https://mavlink.io/en/services/opendroneid.html)) +- [Parameter Protocol](https://mavlink.io/en/services/parameter.html) +- [Parameter Protocol Extended](https://mavlink.io/en/services/parameter_ext.html) — Allows setting string parameters. Used for setting string parameters set in camera definition files. +- [Payload Protocol](https://mavlink.io/en/services/payload.html) +- [Ping Protocol](https://mavlink.io/en/services/ping.html) +- [Standard Modes Protocol](mavlink/standard_modes.md) +- [Terrain Protocol](https://mavlink.io/en/services/terrain.html) +- [Time Synchronization](https://mavlink.io/en/services/timesync.html) +- [Traffic Management (UTM/ADS-B)](https://mavlink.io/en/services/traffic_management.html) +- [Arm Authorization Protocol](https://mavlink.io/en/services/arm_authorization.html) + +## Unsupported + +These services are not supported/used by PX4: + +- [Illuminator Protocol](https://mavlink.io/en/services/illuminator.html) +- [Tunnel Protocol](https://mavlink.io/en/services/tunnel.html) diff --git a/docs/en/middleware/mavlink.md b/docs/en/middleware/mavlink.md index f79efa9c0b..c88fc7840e 100644 --- a/docs/en/middleware/mavlink.md +++ b/docs/en/middleware/mavlink.md @@ -1,87 +1 @@ -# MAVLink Messaging - -[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. - -PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. - -This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices. -It also links instructions for how you can add PX4 support for: - -- [Adding Standard Messages](../mavlink/adding_messages.md) -- [Streaming MAVLink messages](../mavlink/streaming_messages.md) -- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) -- [Custom MAVLink Messages](../mavlink/custom_messages.md) - -::: info -We do not yet cover _command_ handling and sending, or how to implement your own microservices. -::: - -## MAVLink Overview - -MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links. - -_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. -They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. -Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. - -The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement. -Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. -The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. -The command is resent automatically if no acknowledgment is received. -Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. - -[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages. -They are used to communicate information that cannot be sent in a single message, and to deliver features such as reliable communication. -The command protocol described above is one such service. -Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html). - -MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). -The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages. -Note that most generated libraries do not create code to implement microservices. - -The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): - -- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. - The definitions move to `common.xml` if accepted following testing. -- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. - These are supported by many flight stacks, ground stations, and MAVLink peripherals. - Flight stacks that use these definitions are more likely to interoperate. -- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. - They are present on the vast majority of flight stacks and implemented in the same way. -- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. - -The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. - -The protocol relies on each end of the communication having a shared definition of what messages are being sent. -What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition. - - - -## PX4 and MAVLink - -PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. -In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. - -::: info -To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). -During development you can use definitions in `development.xml`. -You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. -::: - -PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). -This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). - -The build toolchain generates the MAVLink 2 C header files at build time. -The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: - -- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). - You can change this to any other definition file, but the file must include `common.xml`. -- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). - -The files are generated into the build directory: `/build//mavlink/`. + From 39e51b2a6b8cd4dd9d937315bef9963f6c14bcca Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 5 Jun 2025 11:08:47 +1000 Subject: [PATCH 110/130] Apply suggestions from code review Co-authored-by: Julian Oes --- docs/en/mavlink/index.md | 2 +- docs/en/mavlink/protocols.md | 6 ++---- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/docs/en/mavlink/index.md b/docs/en/mavlink/index.md index 8b81cbe595..07715e391f 100644 --- a/docs/en/mavlink/index.md +++ b/docs/en/mavlink/index.md @@ -25,7 +25,7 @@ _Messages_ are simplest and most "fundamental" definition in MAVLink, consisting They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. -The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement. +The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement and retransmission (quality of service). Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. The command is resent automatically if no acknowledgment is received. diff --git a/docs/en/mavlink/protocols.md b/docs/en/mavlink/protocols.md index 316c527469..9111fa45f9 100644 --- a/docs/en/mavlink/protocols.md +++ b/docs/en/mavlink/protocols.md @@ -16,16 +16,14 @@ These services are known to be supported in some form: - Camera Protocols - [Camera Protocol v2](https://mavlink.io/en/services/camera.html) - [Camera Definition](https://mavlink.io/en/services/camera_def.html) - - [Camera Protocol v1 (Simple Trigger Protocol)](https://mavlink.io/en/services/camera_v1.html) - [Command Protocol](https://mavlink.io/en/services/command.html) -- [Component Metadata Protocol (WIP)](https://mavlink.io/en/services/component_information.html) -- [Events Interface (WIP)](https://mavlink.io/en/services/events.html) +- [Component Metadata Protocol](https://mavlink.io/en/services/component_information.html) +- [Events Interface](https://mavlink.io/en/services/events.html) - [File Transfer Protocol (FTP)](https://mavlink.io/en/services/ftp.html) - Gimbal Protocols - [Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html) - Can be enabled by [Gimbal Configuration](../advanced/gimbal_control.md#mavlink-gimbal-mnt-mode-out-mavlink) - PX4 an act as a MAVLink Gimbal for one FC-connected Gimbal - - [Gimbal Protocol v1 (superseded)](https://mavlink.io/en/services/gimbal.html) - [Heartbeat/Connection Protocol](https://mavlink.io/en/services/heartbeat.html) - [High Latency Protocol](https://mavlink.io/en/services/high_latency.html) — PX4 streams [HIGH_LATENCY2](https://mavlink.io/en/messages/common.html#HIGH_LATENCY2) - [Image Transmission Protocol](https://mavlink.io/en/services/image_transmission.html) From 485cfa0c0ffcb0ce738f918723a045c287fe0fe0 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 5 Jun 2025 11:15:05 +1000 Subject: [PATCH 111/130] Fix broken link --- docs/en/mavlink/protocols.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/en/mavlink/protocols.md b/docs/en/mavlink/protocols.md index 9111fa45f9..9dac078fb9 100644 --- a/docs/en/mavlink/protocols.md +++ b/docs/en/mavlink/protocols.md @@ -37,7 +37,7 @@ These services are known to be supported in some form: - [Parameter Protocol Extended](https://mavlink.io/en/services/parameter_ext.html) — Allows setting string parameters. Used for setting string parameters set in camera definition files. - [Payload Protocol](https://mavlink.io/en/services/payload.html) - [Ping Protocol](https://mavlink.io/en/services/ping.html) -- [Standard Modes Protocol](mavlink/standard_modes.md) +- [Standard Modes Protocol](../mavlink/standard_modes.md) - [Terrain Protocol](https://mavlink.io/en/services/terrain.html) - [Time Synchronization](https://mavlink.io/en/services/timesync.html) - [Traffic Management (UTM/ADS-B)](https://mavlink.io/en/services/traffic_management.html) From ff2b82dc51cf0d2282a10421db9338572725feaf Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 5 Jun 2025 11:26:54 +1000 Subject: [PATCH 112/130] Move commands into microservices --- docs/en/mavlink/index.md | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/docs/en/mavlink/index.md b/docs/en/mavlink/index.md index 07715e391f..fd364c33a2 100644 --- a/docs/en/mavlink/index.md +++ b/docs/en/mavlink/index.md @@ -25,16 +25,17 @@ _Messages_ are simplest and most "fundamental" definition in MAVLink, consisting They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. -The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement and retransmission (quality of service). +[Microservices](../mavlink/protocols.md) are "meta protocols" built on top of MAVLink messages. +They are used to communicate information that cannot be sent in a single message. + +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) is a service for sending commands that may need acknowledgement and retransmission (quality of service). Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. -The command is resent automatically if no acknowledgment is received. +The command is automatically resent a number of times if no acknowledgment is received. Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. -[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages. -They are used to communicate information that cannot be sent in a single message, and to deliver features such as reliable communication. -The command protocol described above is one such service. -Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html). +Others services include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html), [Parameter Protocol](https://mavlink.io/en/services/parameter.html), and [Mission Protocol](https://mavlink.io/en/services/mission.html). +For more information on what PX4 supports see [Microservices](../mavlink/protocols.md). MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages. From fdc4766da628a89d5e837928a9aed8807b826020 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 4 Jun 2025 20:18:47 +0200 Subject: [PATCH 113/130] Make sure vehicle_thrust_setpoint is always published before vehicle_torque_setpoint After f0b05ea7cfd9de4113f4cd63e8068cf8089bc158 the control allocator only has a callback on the torque setpoint and even though this should work I'm paranoid and would like to avoid surprises by always publishing the thrust before torque then the samples that were published together are also allocated together. --- .../airship_att_control/airship_att_control_main.cpp | 2 +- src/modules/fw_rate_control/FixedwingRateControl.cpp | 2 +- src/modules/fw_rate_control/FixedwingRateControl.hpp | 2 +- src/modules/mc_rate_control/MulticopterRateControl.cpp | 2 +- src/modules/mc_rate_control/MulticopterRateControl.hpp | 2 +- src/modules/vtol_att_control/vtol_att_control_main.cpp | 6 +++--- 6 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/modules/airship_att_control/airship_att_control_main.cpp b/src/modules/airship_att_control/airship_att_control_main.cpp index 2a18b349da..27f12b731f 100644 --- a/src/modules/airship_att_control/airship_att_control_main.cpp +++ b/src/modules/airship_att_control/airship_att_control_main.cpp @@ -126,8 +126,8 @@ AirshipAttitudeControl::Run() if (_vehicle_angular_velocity_sub.update(&angular_velocity)) { /* run the rate controller immediately after a gyro update */ - publishTorqueSetpoint(angular_velocity.timestamp_sample); publishThrustSetpoint(angular_velocity.timestamp_sample); + publishTorqueSetpoint(angular_velocity.timestamp_sample); /* check for updates in manual control topic */ _manual_control_setpoint_sub.update(&_manual_control_setpoint); diff --git a/src/modules/fw_rate_control/FixedwingRateControl.cpp b/src/modules/fw_rate_control/FixedwingRateControl.cpp index 32ac785cda..d7de4e4741 100644 --- a/src/modules/fw_rate_control/FixedwingRateControl.cpp +++ b/src/modules/fw_rate_control/FixedwingRateControl.cpp @@ -44,8 +44,8 @@ FixedwingRateControl::FixedwingRateControl(bool vtol) : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers), _actuator_controls_status_pub(vtol ? ORB_ID(actuator_controls_status_1) : ORB_ID(actuator_controls_status_0)), - _vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_fw) : ORB_ID(vehicle_torque_setpoint)), _vehicle_thrust_setpoint_pub(vtol ? ORB_ID(vehicle_thrust_setpoint_virtual_fw) : ORB_ID(vehicle_thrust_setpoint)), + _vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_fw) : ORB_ID(vehicle_torque_setpoint)), _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")) { _handle_param_vt_fw_difthr_en = param_find("VT_FW_DIFTHR_EN"); diff --git a/src/modules/fw_rate_control/FixedwingRateControl.hpp b/src/modules/fw_rate_control/FixedwingRateControl.hpp index ec3b7e1c9e..2d87e86d8a 100644 --- a/src/modules/fw_rate_control/FixedwingRateControl.hpp +++ b/src/modules/fw_rate_control/FixedwingRateControl.hpp @@ -116,8 +116,8 @@ private: uORB::Publication _actuator_controls_status_pub; uORB::Publication _rate_sp_pub{ORB_ID(vehicle_rates_setpoint)}; uORB::PublicationMulti _rate_ctrl_status_pub{ORB_ID(rate_ctrl_status)}; - uORB::Publication _vehicle_torque_setpoint_pub; uORB::Publication _vehicle_thrust_setpoint_pub; + uORB::Publication _vehicle_torque_setpoint_pub; uORB::Publication _flaps_setpoint_pub{ORB_ID(flaps_setpoint)}; uORB::Publication _spoilers_setpoint_pub{ORB_ID(spoilers_setpoint)}; diff --git a/src/modules/mc_rate_control/MulticopterRateControl.cpp b/src/modules/mc_rate_control/MulticopterRateControl.cpp index 3931125289..a7a8ed4212 100644 --- a/src/modules/mc_rate_control/MulticopterRateControl.cpp +++ b/src/modules/mc_rate_control/MulticopterRateControl.cpp @@ -46,8 +46,8 @@ using math::radians; MulticopterRateControl::MulticopterRateControl(bool vtol) : ModuleParams(nullptr), WorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl), - _vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_mc) : ORB_ID(vehicle_torque_setpoint)), _vehicle_thrust_setpoint_pub(vtol ? ORB_ID(vehicle_thrust_setpoint_virtual_mc) : ORB_ID(vehicle_thrust_setpoint)), + _vehicle_torque_setpoint_pub(vtol ? ORB_ID(vehicle_torque_setpoint_virtual_mc) : ORB_ID(vehicle_torque_setpoint)), _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")) { _vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING; diff --git a/src/modules/mc_rate_control/MulticopterRateControl.hpp b/src/modules/mc_rate_control/MulticopterRateControl.hpp index 1a2427da18..76e488305a 100644 --- a/src/modules/mc_rate_control/MulticopterRateControl.hpp +++ b/src/modules/mc_rate_control/MulticopterRateControl.hpp @@ -107,8 +107,8 @@ private: uORB::Publication _actuator_controls_status_pub{ORB_ID(actuator_controls_status_0)}; uORB::PublicationMulti _controller_status_pub{ORB_ID(rate_ctrl_status)}; uORB::Publication _vehicle_rates_setpoint_pub{ORB_ID(vehicle_rates_setpoint)}; - uORB::Publication _vehicle_torque_setpoint_pub; uORB::Publication _vehicle_thrust_setpoint_pub; + uORB::Publication _vehicle_torque_setpoint_pub; vehicle_control_mode_s _vehicle_control_mode{}; vehicle_status_s _vehicle_status{}; diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp index 353d236ce6..081c5a8106 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -81,8 +81,8 @@ VtolAttitudeControl::VtolAttitudeControl() : _spoilers_setpoint_pub.advertise(); _vtol_vehicle_status_pub.advertise(); _vehicle_thrust_setpoint0_pub.advertise(); - _vehicle_torque_setpoint0_pub.advertise(); _vehicle_thrust_setpoint1_pub.advertise(); + _vehicle_torque_setpoint0_pub.advertise(); _vehicle_torque_setpoint1_pub.advertise(); } @@ -449,10 +449,10 @@ VtolAttitudeControl::Run() _vtol_type->fill_actuator_outputs(); - _vehicle_torque_setpoint0_pub.publish(_torque_setpoint_0); - _vehicle_torque_setpoint1_pub.publish(_torque_setpoint_1); _vehicle_thrust_setpoint0_pub.publish(_thrust_setpoint_0); _vehicle_thrust_setpoint1_pub.publish(_thrust_setpoint_1); + _vehicle_torque_setpoint0_pub.publish(_torque_setpoint_0); + _vehicle_torque_setpoint1_pub.publish(_torque_setpoint_1); // Advertise/publish vtol vehicle status -- immediately if changed, otherwise at 1 Hz const bool vtol_vehicle_status_changed = From 48c54afc850fdba5344f597461d27c29278f799c Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 14 May 2025 14:42:20 +1000 Subject: [PATCH 114/130] ArmingCheckXxxx.msg - uorb docs --- msg/versioned/ArmingCheckReply.msg | 56 ++++++++++++++++------------ msg/versioned/ArmingCheckRequest.msg | 15 ++++++-- 2 files changed, 43 insertions(+), 28 deletions(-) diff --git a/msg/versioned/ArmingCheckReply.msg b/msg/versioned/ArmingCheckReply.msg index 0efcc21738..54e724bdb8 100644 --- a/msg/versioned/ArmingCheckReply.msg +++ b/msg/versioned/ArmingCheckReply.msg @@ -1,35 +1,43 @@ +# Arming check reply. +# +# This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. +# The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). +# The request is sent regularly to all registered ROS modes, even while armed, so that the FMU always knows and can forward the current state. +# +# Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply). +# The message is not used by internal/FMU components, as their mode requirements are known at compile time. + uint32 MESSAGE_VERSION = 1 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start. -uint8 request_id -uint8 registration_id +uint8 request_id # Id of ArmingCheckRequest for which this is a response. +uint8 registration_id # Id of external component emitting this response. -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. -uint8 health_component_index # HEALTH_COMPONENT_INDEX_* -bool health_component_is_present -bool health_component_warning -bool health_component_error +uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). -bool can_arm_and_run # whether arming is possible, and if it's a navigation mode, if it can run +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. -uint8 num_events +uint8 num_events # Number of queued failure messages (Event) in the events field. -Event[5] events +Event[5] events # Arming failure reasons (Queue of events to report to GCS). # Mode requirements -bool mode_req_angular_velocity -bool mode_req_attitude -bool mode_req_local_alt -bool mode_req_local_position -bool mode_req_local_position_relaxed -bool mode_req_global_position -bool mode_req_global_position_relaxed -bool mode_req_mission -bool mode_req_home_position -bool mode_req_prevent_arming -bool mode_req_manual_control +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). +bool mode_req_attitude # Requires an attitude estimate. +bool mode_req_local_alt # Requires a local altitude estimate. +bool mode_req_local_position # Requires a local position estimate. +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. +bool mode_req_global_position # Requires a global position estimate. +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. +bool mode_req_mission # Requires an uploaded mission. +bool mode_req_home_position # Requires a home position (such as RTL/Return mode). +bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_manual_control # Requires a manual controller - -uint8 ORB_QUEUE_LENGTH = 4 +uint8 ORB_QUEUE_LENGTH = 4 # diff --git a/msg/versioned/ArmingCheckRequest.msg b/msg/versioned/ArmingCheckRequest.msg index 17c6e4bacd..37a56e3c4b 100644 --- a/msg/versioned/ArmingCheckRequest.msg +++ b/msg/versioned/ArmingCheckRequest.msg @@ -1,7 +1,14 @@ +# Arming check request. +# +# Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +# All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +# The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. +# +# The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +# The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start. -# broadcast message to request all registered arming checks to be reported - -uint8 request_id +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. From b8fa208bb576f7352b0bc59da9229a288ca92fca Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Mon, 2 Jun 2025 12:13:07 +0200 Subject: [PATCH 115/130] Update NuttX Fixes RT117X OCRAM M7 memory freeze --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index db3dc7b9e6..886acbbdb4 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit db3dc7b9e60b464c759d15f69fc3ee192aefa816 +Subproject commit 886acbbdb4f061e5c0ce1a76afbcfa7cb7df9849 From 5e358560332e86483c5179364228fe67fd193f20 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Wed, 28 May 2025 18:05:43 +1000 Subject: [PATCH 116/130] Generate dds yaml as part of msg_docs generation --- Tools/msg/generate_msg_docs.py | 95 ++++++++++++++++++++++++++++++++++ 1 file changed, 95 insertions(+) diff --git a/Tools/msg/generate_msg_docs.py b/Tools/msg/generate_msg_docs.py index 193c56431f..f8bc70bc10 100755 --- a/Tools/msg/generate_msg_docs.py +++ b/Tools/msg/generate_msg_docs.py @@ -2,6 +2,7 @@ """ Generate docs from .msg files +Also generates docs/en/middleware/dds_topics.md from dds_topics.yaml """ import os @@ -9,6 +10,97 @@ import argparse import sys +import yaml + +def generate_dds_yaml_doc(allMessageFiles, output_file = 'dds_topics.md'): + """ + Generates human readable version of dds_topics.yaml. + Default output is to docs/en/middleware/dds_topics.md + """ + + dds_file_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../src/modules/uxrce_dds_client/dds_topics.yaml") + output_file_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),f"../../docs/en/middleware/{output_file}") + + try: + with open(dds_file_path, 'r') as file: + data = yaml.safe_load(file) + + # Get messages and topics that are not published by default + # Start by getting all that are published. + all_messages_in_source = set() + all_message_types =set() + all_topics =set() + for message in data["publications"]: + all_message_types.add(message['type'].split("::")[-1]) + all_topics.add(message['topic'].split('/')[-1]) + for message in data["subscriptions"]: + all_message_types.add(message['type'].split("::")[-1]) + all_topics.add(message['topic'].split('/')[-1]) + if data["subscriptions_multi"]: # There is none now + dds_markdown += "None\n" + for message in data["subscriptions_multi"]: + all_message_types.add(message['type'].split("::")[-1]) + all_topics.add(message['topic'].split('/')[-1]) + for message in allMessageFiles: + all_messages_in_source.add(message.split('/')[-1].split('.')[0]) + messagesNotExported = all_messages_in_source - all_message_types + + # write out the dds file + dds_markdown="""# dds_topics.yaml + +::: info +This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code. +::: + + +The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). + +This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on. + +## Publications + +Topic | Type| Rate Limit +--- | --- | --- +""" + + for message in data["publications"]: + type = message['type'] + px4Type=type.split("::")[-1] + dds_markdown += f"`{message['topic']}` | [{type}](../msg_docs/{px4Type}.md) | {message.get('rate','')}\n" + + dds_markdown += "\n## Subscriptions\n\nTopic | Type\n--- | ---\n" + + for message in data["subscriptions"]: + type = message['type'] + px4Type=type.split("::")[-1] + dds_markdown += f"{message['topic']} | [{type}](../msg_docs/{px4Type}.md)\n" + + dds_markdown += "\n## Subscriptions Multi\n\n" + + if not data["subscriptions_multi"]: # There is none now + dds_markdown += "None\n" + else: + print("Warning - we now have subscription_multi data - check format") + dds_markdown += "Topic | Type\n--- | ---\n" + for message in data["subscriptions_multi"]: + dds_markdown += f"{message['topic']} | {message['type']}\n" + + if messagesNotExported: + # Print the topics that are not exported to DDS + dds_markdown += "\n## Messages Not Published/Subscribed\n\nThese messages are not listed in the yaml file, and hence are neither published or subscribed\n\n" + for item in messagesNotExported: + dds_markdown += f"[{item}](../msg_docs/{item}.md), " + + #print(dds_markdown) + with open(output_file_path, 'w') as content_file: + content_file.write(dds_markdown) + + except yaml.YAMLError as exc: + print(f"Error parsing YAML: {exc}") + except FileNotFoundError: + print(f"Error: {dds_file_path} not found.") + + def get_msgs_list(msgdir): """ Makes a list of relative paths of .msg files in the given directory @@ -30,6 +122,7 @@ def get_msgs_list(msgdir): if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Generate docs from .msg files') parser.add_argument('-d', dest='dir', help='output directory', required=True) args = parser.parse_args() @@ -132,3 +225,5 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m index_file = os.path.join(output_dir, 'index.md') with open(index_file, 'w') as content_file: content_file.write(index_text) + + generate_dds_yaml_doc(msg_files) From 91ee9f437f6982d53410f78ab3c4a5c8d98c43bf Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Wed, 28 May 2025 18:18:37 +1000 Subject: [PATCH 117/130] Fix up rate-limit and title --- Tools/msg/generate_msg_docs.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/msg/generate_msg_docs.py b/Tools/msg/generate_msg_docs.py index f8bc70bc10..92ed7e22de 100755 --- a/Tools/msg/generate_msg_docs.py +++ b/Tools/msg/generate_msg_docs.py @@ -46,7 +46,7 @@ def generate_dds_yaml_doc(allMessageFiles, output_file = 'dds_topics.md'): messagesNotExported = all_messages_in_source - all_message_types # write out the dds file - dds_markdown="""# dds_topics.yaml + dds_markdown="""# dds_topics.yaml — PX4 Topics Exposed to ROS 2 ::: info This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code. @@ -66,7 +66,7 @@ Topic | Type| Rate Limit for message in data["publications"]: type = message['type'] px4Type=type.split("::")[-1] - dds_markdown += f"`{message['topic']}` | [{type}](../msg_docs/{px4Type}.md) | {message.get('rate','')}\n" + dds_markdown += f"`{message['topic']}` | [{type}](../msg_docs/{px4Type}.md) | {message.get('rate_limit','')}\n" dds_markdown += "\n## Subscriptions\n\nTopic | Type\n--- | ---\n" From 04e1c603f73c3f76a7f3e8f7c4bba4851aaaadf3 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 29 May 2025 12:51:04 +1000 Subject: [PATCH 118/130] Hide unsupported list in twistie --- Tools/msg/generate_msg_docs.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Tools/msg/generate_msg_docs.py b/Tools/msg/generate_msg_docs.py index 92ed7e22de..93a41aeff7 100755 --- a/Tools/msg/generate_msg_docs.py +++ b/Tools/msg/generate_msg_docs.py @@ -87,9 +87,11 @@ Topic | Type| Rate Limit if messagesNotExported: # Print the topics that are not exported to DDS - dds_markdown += "\n## Messages Not Published/Subscribed\n\nThese messages are not listed in the yaml file, and hence are neither published or subscribed\n\n" + dds_markdown += "\n## Messages Exported\n\nThese messages are not listed in the yaml file, and hence are neither published or subscribed." + dds_markdown += "\n\n::: details See messages\n" for item in messagesNotExported: - dds_markdown += f"[{item}](../msg_docs/{item}.md), " + dds_markdown += f"\n- [{item}](../msg_docs/{item}.md)" + dds_markdown += "\n:::\n" # End of details block #print(dds_markdown) with open(output_file_path, 'w') as content_file: From 7008cb0aeba279ed2df9d743cfb9dbedf265c0e6 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 29 May 2025 12:59:55 +1000 Subject: [PATCH 119/130] Tweak words --- Tools/msg/generate_msg_docs.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/msg/generate_msg_docs.py b/Tools/msg/generate_msg_docs.py index 93a41aeff7..18308aed9c 100755 --- a/Tools/msg/generate_msg_docs.py +++ b/Tools/msg/generate_msg_docs.py @@ -87,7 +87,7 @@ Topic | Type| Rate Limit if messagesNotExported: # Print the topics that are not exported to DDS - dds_markdown += "\n## Messages Exported\n\nThese messages are not listed in the yaml file, and hence are neither published or subscribed." + dds_markdown += "\n## Not Exported\n\nThese messages are not listed in the yaml file.\nThey are not build into the module, and hence are neither published or subscribed." dds_markdown += "\n\n::: details See messages\n" for item in messagesNotExported: dds_markdown += f"\n- [{item}](../msg_docs/{item}.md)" From bdb0e4270ca87b0b0e4c19d766b8790fb6ef7544 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Fri, 16 May 2025 11:50:21 -0700 Subject: [PATCH 120/130] ci: updates branch name strategy fixes #24866 Signed-off-by: Ramon Roche --- .github/workflows/build_all_targets.yml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml index ce4229c5b4..69c82fa11c 100644 --- a/.github/workflows/build_all_targets.yml +++ b/.github/workflows/build_all_targets.yml @@ -54,7 +54,13 @@ jobs: run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")" - id: set-branch - run: echo "::set-output name=branchname::${GITHUB_HEAD_REF:-${GITHUB_REF#refs/heads/}}" + run: | + echo "branchname=${{ + github.event_name == 'pull_request' && + format('pr-{0}', github.event.pull_request.number) || + github.head_ref || + github.ref_name + }}" >> $GITHUB_OUTPUT - name: Debug Matrix Output if: runner.debug == '1' From c7ef12545cde8226d57f2462cc4a3ba93424b650 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 4 Jun 2025 11:37:50 +0200 Subject: [PATCH 121/130] mc_att_control_params: lower default roll and pitch attitude gains from 6.5 to 4 6.5 is a relatively high value that was used mostly on smaller, low inertia vehicles ~250-500mm diagonal. There it works great but on larger, higher intertia vehicles this leads to problems. --- src/modules/mc_att_control/mc_att_control_params.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c index 1d7fe08bc4..a503900cff 100644 --- a/src/modules/mc_att_control/mc_att_control_params.c +++ b/src/modules/mc_att_control/mc_att_control_params.c @@ -50,7 +50,7 @@ * @increment 0.1 * @group Multicopter Attitude Control */ -PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.5f); +PARAM_DEFINE_FLOAT(MC_ROLL_P, 4.0f); /** * Pitch P gain @@ -63,7 +63,7 @@ PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.5f); * @increment 0.1 * @group Multicopter Attitude Control */ -PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.5f); +PARAM_DEFINE_FLOAT(MC_PITCH_P, 4.0f); /** * Yaw P gain From 7f4e6189aef300557fce151dbc31d32c66fd95f6 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Thu, 5 Jun 2025 14:43:23 -0800 Subject: [PATCH 122/130] ark_fpv: cleanup board_dma_map.h (#24975) --- .../fpv/nuttx-config/include/board_dma_map.h | 86 ++++--------------- boards/ark/fpv/nuttx-config/nsh/defconfig | 3 +- 2 files changed, 19 insertions(+), 70 deletions(-) diff --git a/boards/ark/fpv/nuttx-config/include/board_dma_map.h b/boards/ark/fpv/nuttx-config/include/board_dma_map.h index adbaaffc20..d1e6f5bd6a 100644 --- a/boards/ark/fpv/nuttx-config/include/board_dma_map.h +++ b/boards/ark/fpv/nuttx-config/include/board_dma_map.h @@ -34,75 +34,25 @@ #pragma once // DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned -// V - -// Timer 4 Channel 1 /* DMA1:29 TIM4CH1 */ - -#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 IIM-42653 */ -#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 IIM-42653 */ - -//#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ -//#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ - -#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ -#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ - -//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ -//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ - -// Timer 8 Channel 1 /* DMA1:47 TIM8CH1 */ -// Timer 8 Channel 2 /* DMA1:48 TIM8CH2 */ -// Timer 8 Channel 3 /* DMA1:49 TIM8CH3 */ -// Timer 8 Channel 4 /* DMA1:50 TIM8CH4 */ - -// Timer 5 Channel 1 /* DMA1:55 TIM5CH1 */ -// Timer 5 Channel 2 /* DMA1:56 TIM5CH2 */ -// Timer 5 Channel 3 /* DMA1:57 TIM5CH3 */ -// Timer 5 Channel 4 /* DMA1:58 TIM5CH4 */ - -// #define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 UART4 */ -// #define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 UART4 */ - -#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 RC */ -// #define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 RC */ - -// Assigned in timer_config.cpp - -// Timer 4 /* 7 DMA1:32 TIM4UP */ -// Timer 5 /* 8 DMA1:50 TIM5UP */ +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 // 1 DMA1:37 IIM-42653 +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 // 2 DMA1:38 IIM-42653 +#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 // 3 DMA1:41 GPS1 +#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 // 4 DMA1:42 GPS1 +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 // 5 DMA1:71 RC +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 // 6 DMA1:72 RC +// Timer 4 (DMAMAP_DMA12_TIM4UP_0) // 7 DMA1:32 TIM4UP/TIM4CH1-4 +// Timer 5 (DMAMAP_DMA12_TIM5UP_0) // 8 DMA1:50 TIM5UP/TIM5CH1-4 // DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned -// V - -// Timer 4 Channel 1 /* DMA2:29 TIM4CH1 */ - -#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* 3 DMA2:43 TELEM3 */ -#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* 4 DMA2:44 TELEM3 */ - -#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ -#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ - -// Timer 8 Channel 1 /* DMA2:47 TIM8CH1 */ -// Timer 8 Channel 2 /* DMA2:48 TIM8CH2 */ -// Timer 8 Channel 3 /* DMA2:49 TIM8CH3 */ -// Timer 8 Channel 4 /* DMA2:50 TIM8CH4 */ - -// Timer 5 Channel 1 /* DMA2:55 TIM5CH1 */ -// Timer 5 Channel 2 /* DMA2:56 TIM5CH2 */ -// Timer 5 Channel 3 /* DMA2:57 TIM5CH3 */ -// Timer 5 Channel 4 /* DMA2:58 TIM5CH4 */ - -//#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ -//#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ - -#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ -#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ - -#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ -#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ +#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 // 1 DMA2:43 VTX +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 // 2 DMA2:65 VTX +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 // 3 DMA2:66 VTX +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 // 4 DMA2:79 TELEM1 +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 // 5 DMA2:80 TELEM1 +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 // 6 DMA2:45 DEBUG +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 // 7 DMA2:46 DEBUG +// available // DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned -// V - -#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ -#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX // 1 BDMA:11 SPI J11 +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX // 2 BDMA:12 SPI J11 diff --git a/boards/ark/fpv/nuttx-config/nsh/defconfig b/boards/ark/fpv/nuttx-config/nsh/defconfig index bf82ccc0b1..e008f43be1 100644 --- a/boards/ark/fpv/nuttx-config/nsh/defconfig +++ b/boards/ark/fpv/nuttx-config/nsh/defconfig @@ -260,8 +260,6 @@ CONFIG_USART1_TXDMA=y CONFIG_USART2_BAUD=57600 CONFIG_USART2_RXBUFSIZE=600 CONFIG_USART2_RXDMA=y -CONFIG_USART2_TXBUFSIZE=1500 -CONFIG_USART2_TXDMA=y CONFIG_USART3_BAUD=57600 CONFIG_USART3_RXBUFSIZE=180 CONFIG_USART3_RXDMA=y @@ -272,6 +270,7 @@ CONFIG_USART6_BAUD=57600 CONFIG_USART6_RXBUFSIZE=600 CONFIG_USART6_RXDMA=y CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USART6_TXDMA=y CONFIG_USBDEV=y CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 From 64989c3b8d062561523a71a68a999b446e50a91e Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Thu, 5 Jun 2025 14:45:28 -0800 Subject: [PATCH 123/130] dshot: add perf counter for hrt callback (15us avg) (#24976) --- .../nuttx/src/px4/stm/stm32_common/dshot/dshot.c | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c index bb4f75b7a7..22e9fda161 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c @@ -48,6 +48,8 @@ #include #include +#include + // This can be overriden for a specific board. #ifndef BOARD_DMA_NUM_DSHOT_CHANNELS #define BOARD_DMA_NUM_DSHOT_CHANNELS 1 @@ -137,6 +139,8 @@ static uint32_t read_fail_nibble[MAX_NUM_CHANNELS_PER_TIMER] = {}; static uint32_t read_fail_crc[MAX_NUM_CHANNELS_PER_TIMER] = {}; static uint32_t read_fail_zero[MAX_NUM_CHANNELS_PER_TIMER] = {}; +static perf_counter_t hrt_callback_perf = NULL; + static void init_timer_config(uint32_t channel_mask) { // Mark timers in use, channels in use, and timers for bidir dshot @@ -206,7 +210,7 @@ static void init_timers_dma_up(void) continue; } - PX4_DEBUG("Allocated DMA UP Timer Index %u", timer_index); + PX4_INFO("Allocated DMA UP Timer Index %u", timer_index); timer_configs[timer_index].initialized = true; } @@ -215,7 +219,7 @@ static void init_timers_dma_up(void) if (timer_configs[timer_index].dma_handle != NULL) { stm32_dmafree(timer_configs[timer_index].dma_handle); timer_configs[timer_index].dma_handle = NULL; - PX4_DEBUG("Freed DMA UP Timer Index %u", timer_index); + PX4_INFO("Freed DMA UP Timer Index %u", timer_index); } } } @@ -275,6 +279,7 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi if (_bidirectional) { PX4_INFO("Bidirectional DShot enabled, only one timer will be used"); + hrt_callback_perf = perf_alloc(PC_ELAPSED, "dshot: callback perf"); } // NOTE: if bidirectional is enabled only 1 timer can be used. This is because Burst mode uses 1 DMA channel per timer @@ -485,6 +490,8 @@ void dma_burst_finished_callback(DMA_HANDLE handle, uint8_t status, void *arg) static void capture_complete_callback(void *arg) { + perf_begin(hrt_callback_perf); + uint8_t timer_index = *((uint8_t *)arg); // Unallocate the timer as CaptureDMA @@ -525,6 +532,8 @@ static void capture_complete_callback(void *arg) // Enable all channels configured as DShotInverted io_timer_set_enable(true, IOTimerChanMode_DshotInverted, IO_TIMER_ALL_MODES_CHANNELS); + + perf_end(hrt_callback_perf); } void process_capture_results(uint8_t timer_index, uint8_t channel_index) From ff87361ffa093bdb9f30f1e59013c9d14c6b29de Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 6 Jun 2025 14:47:21 +0200 Subject: [PATCH 124/130] Navigator: RTL reverse: when landing set next to invalid This makes sure that there is no weird line following logic executed by the flight task when the vehicle should just come down vertical for landing. Signed-off-by: Silvan Fuhrer --- src/modules/navigator/rtl_mission_fast_reverse.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/src/modules/navigator/rtl_mission_fast_reverse.cpp b/src/modules/navigator/rtl_mission_fast_reverse.cpp index c27cd38b56..6abf4cf10f 100644 --- a/src/modules/navigator/rtl_mission_fast_reverse.cpp +++ b/src/modules/navigator/rtl_mission_fast_reverse.cpp @@ -251,6 +251,11 @@ void RtlMissionFastReverse::handleLanding(WorkItemType &new_work_item_type) _mission_item.lon = _home_pos_sub.get().lon; _mission_item.yaw = NAN; + // make previous and next setpoints invalid, such that there will be no line following. + // If the vehicle drifted off the path during back-transition it should just go straight to the landing point. + _navigator->reset_position_setpoint(pos_sp_triplet->previous); + _navigator->reset_position_setpoint(pos_sp_triplet->next); + if ((_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) && do_need_move_to_item()) { new_work_item_type = WorkItemType::WORK_ITEM_TYPE_MOVE_TO_LAND; @@ -261,15 +266,9 @@ void RtlMissionFastReverse::handleLanding(WorkItemType &new_work_item_type) _mission_item.autocontinue = true; _mission_item.time_inside = 0.0f; - // make previous setpoint invalid, such that there will be no prev-current line following. - // if the vehicle drifted off the path during back-transition it should just go straight to the landing point - _navigator->reset_position_setpoint(pos_sp_triplet->previous); - } else { _mission_item.altitude = _home_pos_sub.get().alt; _mission_item.altitude_is_relative = false; - _navigator->reset_position_setpoint(pos_sp_triplet->previous); - _navigator->reset_position_setpoint(pos_sp_triplet->next); _mission_item.land_precision = _param_rtl_pld_md.get(); From 457ce90541204b4ef7f89b3317f6fb2a46b187cb Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 23 May 2025 09:35:26 +0200 Subject: [PATCH 125/130] ekf2: run simplified GNSS checks after initial fix This prevents stopping GNSS fusion on slightly degraded solution when tight checks are set --- .../ekf2/EKF/aid_sources/gnss/gnss_checks.cpp | 30 ++++++++++++++++++- .../ekf2/EKF/aid_sources/gnss/gnss_checks.hpp | 1 + src/modules/ekf2/test/test_EKF_gps.cpp | 11 +++++-- 3 files changed, 39 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp index 6d41f482d5..fc26914693 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp @@ -50,7 +50,7 @@ bool GnssChecks::run(const gnssSample &gnss, uint64_t time_us) bool passed = false; if (_initial_checks_passed) { - if (runInitialFixChecks(gnss)) { + if (runSimplifiedChecks(gnss)) { _time_last_pass_us = time_us; passed = isTimedOut(_time_last_fail_us, time_us, math::max((uint64_t)1e6, (uint64_t)_params.min_health_time_us / 10)); @@ -79,6 +79,34 @@ bool GnssChecks::run(const gnssSample &gnss, uint64_t time_us) return passed; } +bool GnssChecks::runSimplifiedChecks(const gnssSample &gnss) +{ + _check_fail_status.flags.fix = (gnss.fix_type < 3); + + // Check the reported horizontal and vertical position accuracy + _check_fail_status.flags.hacc = (gnss.hacc > 50.f); + _check_fail_status.flags.vacc = (gnss.vacc > 50.f); + + // Check the reported speed accuracy + _check_fail_status.flags.sacc = (gnss.sacc > 10.f); + + _check_fail_status.flags.spoofed = gnss.spoofed; + + bool passed = true; + + if ( + _check_fail_status.flags.fix || + (_check_fail_status.flags.hacc && isCheckEnabled(GnssChecksMask::kHacc)) || + (_check_fail_status.flags.vacc && isCheckEnabled(GnssChecksMask::kVacc)) || + (_check_fail_status.flags.sacc && isCheckEnabled(GnssChecksMask::kSacc)) || + (_check_fail_status.flags.spoofed && isCheckEnabled(GnssChecksMask::kSpoofed)) + ) { + passed = false; + } + + return passed; +} + bool GnssChecks::runInitialFixChecks(const gnssSample &gnss) { // Check the fix type diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp index af64678271..a8fdb39b90 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp @@ -112,6 +112,7 @@ private: bool isCheckEnabled(GnssChecksMask check) { return (_params.check_mask & static_cast(check)); } + bool runSimplifiedChecks(const gnssSample &gnss); bool runInitialFixChecks(const gnssSample &gnss); void runOnGroundGnssChecks(const gnssSample &gnss); diff --git a/src/modules/ekf2/test/test_EKF_gps.cpp b/src/modules/ekf2/test/test_EKF_gps.cpp index f6aae937df..cc738a3f6f 100644 --- a/src/modules/ekf2/test/test_EKF_gps.cpp +++ b/src/modules/ekf2/test/test_EKF_gps.cpp @@ -84,12 +84,19 @@ TEST_F(EkfGpsTest, gpsTimeout) // WHEN: the number of satellites drops below the minimum _sensor_simulator._gps.setNumberOfSatellites(3); + // THEN: the GNSS fusion does not stop because other metrics are good enough + _sensor_simulator.runSeconds(8); + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsFusion()); + + // WHEN: the fix type drops + _sensor_simulator._gps.setFixType(0); + // THEN: the GNSS fusion stops after some time _sensor_simulator.runSeconds(8); EXPECT_FALSE(_ekf_wrapper.isIntendingGpsFusion()); - // BUT WHEN: the number of satellites is good again - _sensor_simulator._gps.setNumberOfSatellites(16); + // BUT WHEN: the fix type is good again + _sensor_simulator._gps.setFixType(3); // THEN: the GNSS fusion restarts _sensor_simulator.runSeconds(6); From e346e241585413fcddb70c419b3477f69ca4ecf4 Mon Sep 17 00:00:00 2001 From: Balduin Date: Fri, 6 Jun 2025 20:30:56 +0200 Subject: [PATCH 126/130] gz: Use pose specified by PX4_GZ_MODEL_POSE (#24956) * gz: use pose specified by PX4_GZ_MODEL_POSE * gz: fix empty PX4_GZ_MODEL_POSE case * gz: no pose rather than zero on empty argument --- ROMFS/px4fmu_common/init.d-posix/px4-rc.gzsim | 35 ++++++++++++------- 1 file changed, 23 insertions(+), 12 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/px4-rc.gzsim b/ROMFS/px4fmu_common/init.d-posix/px4-rc.gzsim index f610c19af0..ee24d195a7 100644 --- a/ROMFS/px4fmu_common/init.d-posix/px4-rc.gzsim +++ b/ROMFS/px4fmu_common/init.d-posix/px4-rc.gzsim @@ -110,25 +110,36 @@ if [ -n "${PX4_SIM_MODEL#*gz_}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then MODEL_NAME="${PX4_SIM_MODEL#*gz_}" MODEL_NAME_INSTANCE="${MODEL_NAME}_${px4_instance}" - POSE_ARG="" - if [ -n "${PX4_GZ_MODEL_POSE}" ]; then - pos_x=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $1}') - pos_y=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $2}') - pos_z=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $3}') - pos_x=${pos_x:-0} - pos_y=${pos_y:-0} - pos_z=${pos_z:-0} + sdf_pose_str="" - POSE_ARG=", pose: { position: { x: ${pos_x}, y: ${pos_y}, z: ${pos_z} } }" - echo "INFO [init] Spawning model at position: ${pos_x} ${pos_y} ${pos_z}" + if [ -n "${PX4_GZ_MODEL_POSE}" ]; then + pose_x=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $1}') + pose_y=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $2}') + pose_z=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $3}') + pose_roll=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $4}') + pose_pitch=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $5}') + pose_yaw=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $6}') + + pose_x=${pose_x:-0} + pose_y=${pose_y:-0} + pose_z=${pose_z:-0} + pose_roll=${pose_roll:-0} + pose_pitch=${pose_pitch:-0} + pose_yaw=${pose_yaw:-0} + + sdf_pose_str=" ${pose_x} ${pose_y} ${pose_z} ${pose_roll} ${pose_pitch} ${pose_yaw} " + echo "INFO [init] Gazebo model pose: ${pose_x} ${pose_y} ${pose_z} ${pose_roll} ${pose_pitch} ${pose_yaw}" fi - echo "INFO [init] Spawning model" + echo "INFO [init] Spawning Gazebo model" + + # include the actual SDF in this one, containing the pose if given + sdf_str=" file://${PX4_GZ_MODELS}/${MODEL_NAME}/model.sdf ${sdf_pose_str} " # Spawn model ${gz_command} service -s "/world/${PX4_GZ_WORLD}/create" --reqtype gz.msgs.EntityFactory \ --reptype gz.msgs.Boolean --timeout 5000 \ - --req "sdf_filename: \"${PX4_GZ_MODELS}/${MODEL_NAME}/model.sdf\", name: \"${MODEL_NAME_INSTANCE}\", allow_renaming: false${POSE_ARG}" > /dev/null 2>&1 + --req "name: \"${MODEL_NAME_INSTANCE}\", allow_renaming: false, sdf: '${sdf_str}'" > /dev/null 2>&1 # Wait for model to spawn sleep 1 From c0f6cfa30fb611899f5e887de8af92ae91494ee2 Mon Sep 17 00:00:00 2001 From: Crowdin Bot Date: Sun, 8 Jun 2025 00:11:14 +0000 Subject: [PATCH 127/130] New Crowdin translations - ko --- docs/ko/SUMMARY.md | 6 +- docs/ko/dev_log/log_encryption.md | 2 +- docs/ko/flight_controller/kakuteh7-wing.md | 10 +- docs/ko/flight_modes_rover/ackermann.md | 2 +- docs/ko/flight_modes_rover/differential.md | 2 +- docs/ko/flight_modes_rover/mecanum.md | 2 +- docs/ko/frames_rover/ackermann.md | 2 +- docs/ko/frames_rover/differential.md | 2 +- docs/ko/frames_rover/mecanum.md | 2 +- docs/ko/mavlink/index.md | 89 +++++++ docs/ko/mavlink/protocols.md | 51 ++++ docs/ko/middleware/mavlink.md | 88 +------ docs/ko/middleware/uorb.md | 4 +- docs/ko/middleware/uxrce_dds.md | 5 +- docs/ko/releases/1.16.md | 221 ++++++++++++++++++ docs/ko/releases/index.md | 3 +- docs/ko/releases/main.md | 73 +----- docs/ko/ros2/px4_ros2_control_interface.md | 6 +- docs/ko/ros2/px4_ros2_msg_translation_node.md | 4 +- docs/ko/ros2/user_guide.md | 4 +- docs/ko/sim_gazebo_gz/worlds.md | 2 +- docs/ko/telemetry/jfi_telemetry.md | 2 +- 22 files changed, 404 insertions(+), 178 deletions(-) create mode 100644 docs/ko/mavlink/index.md create mode 100644 docs/ko/mavlink/protocols.md create mode 100644 docs/ko/releases/1.16.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index a41e987808..b559b40696 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -725,12 +725,13 @@ - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - - [MAVLink Messaging](middleware/mavlink.md) + - [MAVLink Messaging](mavlink/index.md) - [Adding Messages](mavlink/adding_messages.md) - [Streaming Messages](mavlink/streaming_messages.md) - [Receiving Messages](mavlink/receiving_messages.md) - [Custom MAVLink Messages](mavlink/custom_messages.md) - - [Standard Modes Protocol](mavlink/standard_modes.md) + - [Protocols/Microservices](mavlink/protocols.md) + - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [모듈과 명령어](modules/modules_main.md) - [자동 튜닝](modules/modules_autotune.md) @@ -860,6 +861,7 @@ - [출시](releases/index.md) - [main (alpha)](releases/main.md) + - [1.16 (release candidate)](releases/1.16.md) - [1.15 (stable)](releases/1.15.md) - [1.14](releases/1.14.md) - [1.13](releases/1.13.md) diff --git a/docs/ko/dev_log/log_encryption.md b/docs/ko/dev_log/log_encryption.md index 59bfd961e1..5fdb48e126 100644 --- a/docs/ko/dev_log/log_encryption.md +++ b/docs/ko/dev_log/log_encryption.md @@ -12,7 +12,7 @@ To use it you will need to build firmware with this feature enabled and then upl ::: :::tip -Log encryption was has been improved in PX4 main (v1.16+) to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). +Log encryption was has been improved in PX4 v1.16 to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). In earlier versions the encrypted symmetric key was stored in a separate file. For more information see the [Log Encryption (PX4 v1.15)](https://docs.px4.io/v1.15/en/dev_log/log_encryption.html). diff --git a/docs/ko/flight_controller/kakuteh7-wing.md b/docs/ko/flight_controller/kakuteh7-wing.md index 4977f57f23..52868213ba 100644 --- a/docs/ko/flight_controller/kakuteh7-wing.md +++ b/docs/ko/flight_controller/kakuteh7-wing.md @@ -1,4 +1,6 @@ -# Holybro Kakute H7 V2 +# Holybro Kakute H743-Wing + + :::warning PX4 does not manufacture this (or any) autopilot. @@ -31,9 +33,7 @@ The board can be bought from one of the following shops (for example): | Buz-, Buz+ | Piezo buzzer | | | M1 to M14 | Motor signal outputs | | - - -## 부트로더 업데이트 +## PX4 Bootloader Update {#bootloader} The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki). Before the PX4 firmware can be installed, the _PX4 bootloader_ must be flashed. @@ -50,7 +50,7 @@ make holybro_kakuteh7-wing_default ## 펌웨어 설치 :::info -KakuteH7-wing is supported with PX4 master & PX4 v1.16 or newer.. +KakuteH7-wing is supported in PX4 v1.16 or newer. Prior to that release you will need to manually build and install the firmware. ::: diff --git a/docs/ko/flight_modes_rover/ackermann.md b/docs/ko/flight_modes_rover/ackermann.md index b642013fb7..6dff34ad6e 100644 --- a/docs/ko/flight_modes_rover/ackermann.md +++ b/docs/ko/flight_modes_rover/ackermann.md @@ -137,7 +137,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | 통신 | 설명 | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------- | diff --git a/docs/ko/flight_modes_rover/differential.md b/docs/ko/flight_modes_rover/differential.md index 991c521d20..3e21a99f05 100644 --- a/docs/ko/flight_modes_rover/differential.md +++ b/docs/ko/flight_modes_rover/differential.md @@ -115,7 +115,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | 통신 | 설명 | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ | diff --git a/docs/ko/flight_modes_rover/mecanum.md b/docs/ko/flight_modes_rover/mecanum.md index 85f05d238e..8e86e8afb1 100644 --- a/docs/ko/flight_modes_rover/mecanum.md +++ b/docs/ko/flight_modes_rover/mecanum.md @@ -140,7 +140,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | 통신 | 설명 | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ | diff --git a/docs/ko/frames_rover/ackermann.md b/docs/ko/frames_rover/ackermann.md index 80575a7ee9..3a8c1c191e 100644 --- a/docs/ko/frames_rover/ackermann.md +++ b/docs/ko/frames_rover/ackermann.md @@ -1,6 +1,6 @@ # Ackermann Rovers - + An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates. This kind of steering is used on most commercial vehicles, including cars, trucks etc. diff --git a/docs/ko/frames_rover/differential.md b/docs/ko/frames_rover/differential.md index a74fbd1d50..95ffe04993 100644 --- a/docs/ko/frames_rover/differential.md +++ b/docs/ko/frames_rover/differential.md @@ -1,6 +1,6 @@ # Differential Rovers - + A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate. Forward motion is achieved by driving both wheels at the same speed in the same direction. diff --git a/docs/ko/frames_rover/mecanum.md b/docs/ko/frames_rover/mecanum.md index 7d9a249156..548e7bcf4c 100644 --- a/docs/ko/frames_rover/mecanum.md +++ b/docs/ko/frames_rover/mecanum.md @@ -1,6 +1,6 @@ # Mecanum Rovers - + A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first. Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place. diff --git a/docs/ko/mavlink/index.md b/docs/ko/mavlink/index.md new file mode 100644 index 0000000000..53ed4c4a1f --- /dev/null +++ b/docs/ko/mavlink/index.md @@ -0,0 +1,89 @@ +# MAVLink 메시징 + +[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. + +PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. + +This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices. +It also links instructions for how you can add PX4 support for: + +- [Adding Standard Messages](../mavlink/adding_messages.md) +- [Streaming MAVLink messages](../mavlink/streaming_messages.md) +- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) +- [Custom MAVLink Messages](../mavlink/custom_messages.md) +- [Protocols/Microservices](../mavlink/protocols.md) + +:::info +We do not yet cover _command_ handling and sending, or how to implement your own microservices. +::: + +## MAVLink Overview + +MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links. + +_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. +They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. +Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. + +[Microservices](../mavlink/protocols.md) are "meta protocols" built on top of MAVLink messages. +They are used to communicate information that cannot be sent in a single message. + +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) is a service for sending commands that may need acknowledgement and retransmission (quality of service). +Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. +The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. +The command is automatically resent a number of times if no acknowledgment is received. +Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. + +Others services include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html), [Parameter Protocol](https://mavlink.io/en/services/parameter.html), and [Mission Protocol](https://mavlink.io/en/services/mission.html). +For more information on what PX4 supports see [Microservices](../mavlink/protocols.md). + +MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). +The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages. +Note that most generated libraries do not create code to implement microservices. + +The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): + +- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. + The definitions move to `common.xml` if accepted following testing. +- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. + These are supported by many flight stacks, ground stations, and MAVLink peripherals. + Flight stacks that use these definitions are more likely to interoperate. +- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. + They are present on the vast majority of flight stacks and implemented in the same way. +- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. + +The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. + +The protocol relies on each end of the communication having a shared definition of what messages are being sent. +What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition. + + + +## PX4 and MAVLink + +PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. +In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. + +:::info +To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). +During development you can use definitions in `development.xml`. +You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. +::: + +PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). +This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). + +The build toolchain generates the MAVLink 2 C header files at build time. +The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: + +- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). + You can change this to any other definition file, but the file must include `common.xml`. +- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). + +The files are generated into the build directory: `/build//mavlink/`. diff --git a/docs/ko/mavlink/protocols.md b/docs/ko/mavlink/protocols.md new file mode 100644 index 0000000000..e169080ae9 --- /dev/null +++ b/docs/ko/mavlink/protocols.md @@ -0,0 +1,51 @@ +# MAVLink Microservices (Protocols) + +MAVLink "microservices" are a protocols that use multiple messages exchanged between components to communicate more complicated information. +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) provides an efficient mechanism for packaging a command in a (particular) message and receiving acknowledgement of the command in another message. + +MAVLink microservices are documented the [MAVLink Guide](https://mavlink.io/en/services/) (this is not exhaustive: not all messages are grouped into protocols and not all protocols are documented). + +This section lists the services known to be supported/not supported by PX4 in this version. + +## Supported Microservices + +These services are known to be supported in some form: + +- [Battery Protocol](https://mavlink.io/en/services/battery.html) + - [BATTERY_STATUS](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) and [BATTERY_INFO](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) are streamed. +- Camera Protocols + - [Camera Protocol v2](https://mavlink.io/en/services/camera.html) + - [Camera Definition](https://mavlink.io/en/services/camera_def.html) +- [Command Protocol](https://mavlink.io/en/services/command.html) +- [Component Metadata Protocol](https://mavlink.io/en/services/component_information.html) +- [Events Interface](https://mavlink.io/en/services/events.html) +- [File Transfer Protocol (FTP)](https://mavlink.io/en/services/ftp.html) +- Gimbal Protocols + - [Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html) + - Can be enabled by [Gimbal Configuration](../advanced/gimbal_control.md#mavlink-gimbal-mnt-mode-out-mavlink) + - PX4 an act as a MAVLink Gimbal for one FC-connected Gimbal +- [Heartbeat/Connection Protocol](https://mavlink.io/en/services/heartbeat.html) +- [High Latency Protocol](https://mavlink.io/en/services/high_latency.html) — PX4 streams [HIGH_LATENCY2](https://mavlink.io/en/messages/common.html#HIGH_LATENCY2) +- [Image Transmission Protocol](https://mavlink.io/en/services/image_transmission.html) +- [Landing Target Protocol](https://mavlink.io/en/services/landing_target.html) +- [Manual Control (Joystick) Protocol](https://mavlink.io/en/services/manual_control.html) +- [MAVLink Id Assignment (sysid, compid)](https://mavlink.io/en/services/mavlink_id_assignment.html) +- [Mission Protocol](https://mavlink.io/en/services/mission.html) +- [Offboard Control Protocol](https://mavlink.io/en/services/offboard_control.html) +- [Remote ID](../peripherals/remote_id.md) ([Open Drone ID Protocol](https://mavlink.io/en/services/opendroneid.html)) +- [Parameter Protocol](https://mavlink.io/en/services/parameter.html) +- [Parameter Protocol Extended](https://mavlink.io/en/services/parameter_ext.html) — Allows setting string parameters. Used for setting string parameters set in camera definition files. +- [Payload Protocol](https://mavlink.io/en/services/payload.html) +- [Ping Protocol](https://mavlink.io/en/services/ping.html) +- [Standard Modes Protocol](../mavlink/standard_modes.md) +- [Terrain Protocol](https://mavlink.io/en/services/terrain.html) +- [Time Synchronization](https://mavlink.io/en/services/timesync.html) +- [Traffic Management (UTM/ADS-B)](https://mavlink.io/en/services/traffic_management.html) +- [Arm Authorization Protocol](https://mavlink.io/en/services/arm_authorization.html) + +## 미지원 + +These services are not supported/used by PX4: + +- [Illuminator Protocol](https://mavlink.io/en/services/illuminator.html) +- [Tunnel Protocol](https://mavlink.io/en/services/tunnel.html) diff --git a/docs/ko/middleware/mavlink.md b/docs/ko/middleware/mavlink.md index 671b5fc149..c88fc7840e 100644 --- a/docs/ko/middleware/mavlink.md +++ b/docs/ko/middleware/mavlink.md @@ -1,87 +1 @@ -# MAVLink 메시징 - -[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. - -PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. - -This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices. -It also links instructions for how you can add PX4 support for: - -- [Adding Standard Messages](../mavlink/adding_messages.md) -- [Streaming MAVLink messages](../mavlink/streaming_messages.md) -- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) -- [Custom MAVLink Messages](../mavlink/custom_messages.md) - -:::info -We do not yet cover _command_ handling and sending, or how to implement your own microservices. -::: - -## MAVLink Overview - -MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links. - -_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. -They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. -Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. - -The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement. -Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. -The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. -The command is resent automatically if no acknowledgment is received. -Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. - -[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages. -They are used to communicate information that cannot be sent in a single message, and to deliver features such as reliable communication. -The command protocol described above is one such service. -Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html). - -MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). -The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages. -Note that most generated libraries do not create code to implement microservices. - -The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): - -- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. - The definitions move to `common.xml` if accepted following testing. -- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. - These are supported by many flight stacks, ground stations, and MAVLink peripherals. - Flight stacks that use these definitions are more likely to interoperate. -- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. - They are present on the vast majority of flight stacks and implemented in the same way. -- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. - -The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. - -The protocol relies on each end of the communication having a shared definition of what messages are being sent. -What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition. - - - -## PX4 and MAVLink - -PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. -In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. - -:::info -To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). -During development you can use definitions in `development.xml`. -You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. -::: - -PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). -This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). - -The build toolchain generates the MAVLink 2 C header files at build time. -The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: - -- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). - You can change this to any other definition file, but the file must include `common.xml`. -- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). - -The files are generated into the build directory: `/build//mavlink/`. + diff --git a/docs/ko/middleware/uorb.md b/docs/ko/middleware/uorb.md index d004aa9ff9..77b47e3229 100644 --- a/docs/ko/middleware/uorb.md +++ b/docs/ko/middleware/uorb.md @@ -116,9 +116,9 @@ As there are external tools using uORB messages from log files, such as [Flight ## Message Versioning - + -Optional message versioning was introduced in the `main` branch (planned for PX4 v1.16+) to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. +Optional message versioning was introduced PX4 v1.16 to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. Versioned messages are designed to remain more stable over time compared to their non-versioned counterparts, as they are intended to be used across multiple releases of PX4 and external systems, ensuring greater compatibility over longer periods. Versioned messages include an additional field `uint32 MESSAGE_VERSION = x`, where `x` corresponds to the current version of the message. diff --git a/docs/ko/middleware/uxrce_dds.md b/docs/ko/middleware/uxrce_dds.md index 26c237a92c..ab91044dd8 100644 --- a/docs/ko/middleware/uxrce_dds.md +++ b/docs/ko/middleware/uxrce_dds.md @@ -430,16 +430,17 @@ publications: - topic: /fmu/out/collision_constraints type: px4_msgs::msg::CollisionConstraints + rate_limit: 50. # Limit max publication rate to 50 Hz ... - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry - rate_limit: 150. + # Use default publication rate limit of 100 Hz - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus - rate_limit: 50. + rate_limit: 5. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint diff --git a/docs/ko/releases/1.16.md b/docs/ko/releases/1.16.md new file mode 100644 index 0000000000..7e5bc0f736 --- /dev/null +++ b/docs/ko/releases/1.16.md @@ -0,0 +1,221 @@ +# PX4-Autopilot v1.16.0 Release Notes + + + + + +
    +
    +

    This page is on a release branch, and hence possibly out of date. See the latest version.

    +
    +
    + +This document covers all changes in PX4 v1.16.0 since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)). + +:::info +These notes include only changes merged in 2023 and later — commits before 2023 are not listed. +::: + +## Read Before Upgrading + +Please continue reading for [upgrade instructions](#upgrade-guide). + +## Major Changes + +- **Rover support rework** + - New dedicated firmware build for rovers (airframe IDs 50000–52000) + - Separate modules for Ackermann, differential and mecanum rovers, each with manual, acro, stabilized, position and auto modes + - Shared pure-pursuit guidance library for all rover modules + - Legacy rover position control module deprecated in favor of the new modules + +## Upgrade Guide + +- [PX4-Autopilot#24648](https://github.com/PX4/PX4-Autopilot/pull/24648): Added setting default for EKF2_EV_CTRL to 15 for VOXL 2 boards +- [PX4-Autopilot#22517](https://github.com/PX4/PX4-Autopilot/pull/22517): Change default ethernet IP +- [PX4-Autopilot#24602](https://github.com/PX4/PX4-Autopilot/pull/24602): remove serial port default from sf45 module + +## Other changes + +### Hardware Support + +- **[New Hardware]** [PX4-Autopilot#23830](https://github.com/PX4/PX4-Autopilot/pull/23830): Boards: ARK FPV FC +- **[New Hardware]** [PX4-Autopilot#23414](https://github.com/PX4/PX4-Autopilot/pull/23414): board: add cuav 7-nano +- **[New Hardware]** [PX4-Autopilot#24769](https://github.com/PX4/PX4-Autopilot/pull/24769): add new board corvon743v1 +- **[New Hardware]** [PX4-Autopilot#24018](https://github.com/PX4/PX4-Autopilot/pull/24018): boards: bluerobotics: navigator: Add initial support +- **[New Hardware]** [PX4-Autopilot#24147](https://github.com/PX4/PX4-Autopilot/pull/24147): boards: add new board micoair743-v2 +- **[New Hardware]** [PX4-Autopilot#23218](https://github.com/PX4/PX4-Autopilot/pull/23218): boards: add new board micoair h743 +- **[New Hardware]** [PX4-Autopilot#24512](https://github.com/PX4/PX4-Autopilot/pull/24512): boards: Add FMUv6s target +- **[New Hardware]** [PX4-Autopilot#23927](https://github.com/PX4/PX4-Autopilot/pull/23927): manifest: Add Skynode S baseboard +- **[New Hardware]** [PX4-Autopilot#23257](https://github.com/PX4/PX4-Autopilot/pull/23257): Add Tropic VMU board support (Baseboard for Teensy 4.1) +- **[New Hardware]** [PX4-Autopilot#23697](https://github.com/PX4/PX4-Autopilot/pull/23697): boards: add new board X-MAV AP-H743v2 +- **[New Hardware]** [PX4-Autopilot#23551](https://github.com/PX4/PX4-Autopilot/pull/23551): 3DR boards: Support for 3DR Control Zero H7 OEM Rev G +- **[New Hardware]** [PX4-Autopilot#23623](https://github.com/PX4/PX4-Autopilot/pull/23623): new board support ZeroOne x6 + +### 공통 + +- [Optical flow scaling factor - SENS_FLOW_SCALE](../sensor/optical_flow.md#scale-factor). ([PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936)). + +- [PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813): Reintroduce optional parameter versioning mechanism for airframe maintainers + +- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). + - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. + - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). + +- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. + The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). + +- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. + This makes log decryption much easier, as there is no need to download or identify a separate key file. + ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). + +- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. + Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. + This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. + ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). + +- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) + +- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. + This typically reduces false warnings due to magnetometer inconsistencies. + ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). + +### 제어 + +- [PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863): [Sponsored by ARK] Bidirectional DShot + +- [PX4-Autopilot#24196](https://github.com/PX4/PX4-Autopilot/pull/24196): Make control allocation and actuator effectiveness a non-module-specific library + +- [PX4-Autopilot#24221](https://github.com/PX4/PX4-Autopilot/pull/24221): Spacecraft Build and Bare Control Allocator + +- Configurable multicopter orbit-mode yaw via `MC_ORBIT_YAW_MOD` ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) + +- Collision prevention now works in manual (acceleration-based) flight mode (`MPC_POS_MODE`) ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507)) + +### Estimation + +- [PX4-Autopilot#23854](https://github.com/PX4/PX4-Autopilot/pull/23854): EKF2: ellipsoidal earth navigation + +- [PX4-Autopilot#23263](https://github.com/PX4/PX4-Autopilot/pull/23263): EKF2: Terrain state + +- [PX4-Autopilot#23185](https://github.com/PX4/PX4-Autopilot/pull/23185): ekf2: add mag type init + +- [PX4-Autopilot#23436](https://github.com/PX4/PX4-Autopilot/pull/23436): ekf2: Optical flow enabled by default + +- Position-loss failsafe delay removed; triggers 1 s after loss (see Common) + +### 센서 + +- [PX4-Autopilot#23656](https://github.com/PX4/PX4-Autopilot/pull/23656): Implemented AUAV absolute/differential pressure sensor support + +- [PX4-Autopilot#23639](https://github.com/PX4/PX4-Autopilot/pull/23639): Implemented temperature sensor support for INA228 / INA238 + +- [PX4-Autopilot#22744](https://github.com/PX4/PX4-Autopilot/pull/22744): Add Ublox ZED-F9P-15B + +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Mag cal: automatically disable internal mags if external ones are available + +- [PX4-Autopilot#23064](https://github.com/PX4/PX4-Autopilot/pull/23064): BMP581: Add Bosch BMP581 barometer + +- [PX4-Autopilot#22914](https://github.com/PX4/PX4-Autopilot/pull/22914): Murata SCH16T IMU driver + +- [PX4-Autopilot#23023](https://github.com/PX4/PX4-Autopilot/pull/23023): ST IIS2MDC Magnetometer driver + +- [PX4-Autopilot#24121](https://github.com/PX4/PX4-Autopilot/pull/24121): Include distance sensor in dds topics + +- [PX4-Autopilot#23925](https://github.com/PX4/PX4-Autopilot/pull/23925): drivers: magnetometer: mmc5983ma: Add SPI support + +- [PX4-Autopilot#23909](https://github.com/PX4/PX4-Autopilot/pull/23909): drivers/magnetometer/ak09916: Add support to AK09915 + +- [PX4-Autopilot#23362](https://github.com/PX4/PX4-Autopilot/pull/23362): Add Bosch BMM350 magnetometer + +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Compass calibration now disables internal compass when external unit present, reducing false warnings + +### 시뮬레이션 + +- **SIH**: + - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. + ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). + - SIH now supports the standard VTOL airframe + ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). +- **Gazebo**: + - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. + The default installer scripts (used for CI) and documentation have been updated. + This is required because Garden end-of-life is Nov 2024. + ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) + - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). + - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). + - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). + - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). + - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). + - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). + - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) + - [PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471): Gazebo: Moving platform + +### uXRCE-DDS / ROS2 + +- **[Feature]** [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically +- [PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582): dds_topics: add vtol_vehicle_status +- [PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583): dds_topics: add home_position + +### MAVLink + +- TBD + +### Multi-Rotor + +- [PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173): [Multirotor] add yaw torque low pass filter + +- [PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943): Add gz model for quadtailsitter + +- [PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358): Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) + +- [PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507): Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). + +### 수직이착륙기(VTOL) + +- TBD + +### Fixed-wing + +- [PX4-Autopilot#24167](https://github.com/PX4/PX4-Autopilot/pull/24167): Fixedwing: fix wheel controller + +- [PX4-Autopilot#23520](https://github.com/PX4/PX4-Autopilot/pull/23520): FixedWing: allow position control without valid global position + +- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) + +### 탐사선 + +This release contains a major rework for the rover support in PX4: + +- Complete restructure of the [rover related documentation](../frames_rover/index.md). +- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). +- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): + - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). +- New module dedicated to [differential rovers](../frames_rover/differential.md): + - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). +- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): + - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). +- Added rover-specific firmware build (`50000–52000`) for Ackermann, differential and mecanum rovers +- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). + This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): + - Generic Differential Rover `50000`. + - Generic Ackermann Rover `51000`. + - Axial SCX10 2 Trail Honcho `51001`. + - Generic Mecanum Rover `52000`. +- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. +- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). +- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. + +### Infrastructure + +- [PX4-Autopilot#24011](https://github.com/PX4/PX4-Autopilot/pull/24011): standard_modes: add vehicle-type specific standard modes +- [PX4-Autopilot#24020](https://github.com/PX4/PX4-Autopilot/pull/24020): ci: build all upload to releases +- [PX4-Autopilot#24002](https://github.com/PX4/PX4-Autopilot/pull/24002): ci: px4-dev container +- [PX4-Autopilot#23937](https://github.com/PX4/PX4-Autopilot/pull/23937): ci: workflow for ubuntu 24 +- [PX4-Autopilot#23869](https://github.com/PX4/PX4-Autopilot/pull/23869): ci: add test for Ubuntu 22.04 +- [PX4-Autopilot#23574](https://github.com/PX4/PX4-Autopilot/pull/23574): ci: try runs-on Dronecode Infra +- [PX4-Autopilot#23550](https://github.com/PX4/PX4-Autopilot/pull/23550): ci: replace build workflows diff --git a/docs/ko/releases/index.md b/docs/ko/releases/index.md index f42bfc9aa1..7df22a6bf7 100644 --- a/docs/ko/releases/index.md +++ b/docs/ko/releases/index.md @@ -2,7 +2,8 @@ PX4 릴리스 노트는 각 릴리스의 변경 사항들을 설명합니다. -- [main](../releases/main.md) (changes since v1.15) +- [main](../releases/main.md) (changes since v1.16) +- [v1.16](../releases/1.16.md) - [v1.15](../releases/1.15.md) - [v1.14](../releases/1.14.md) - [v1.13](../releases/1.13.md) diff --git a/docs/ko/releases/main.md b/docs/ko/releases/main.md index 0e6c07f146..82036f6315 100644 --- a/docs/ko/releases/main.md +++ b/docs/ko/releases/main.md @@ -9,15 +9,15 @@ const { site } = useData();
    -

    This page is on a release bramch, and hence probably out of date. See the latest version.

    +

    This page is on a release branch, and hence probably out of date. See the latest version.

    -This contains changes to PX4 `main` branch since the last major release ([PX v1.15](../releases/1.15.md)). +This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)). :::warning -The PX4 v1.15 release is in beta testing, pending release. -Update these notes with features that are going to be in `main` but not the PX4 v1.15 release. +PX4 v1.16 is in candidate-release testing, pending release. +Update these notes with features that are going to be in `main` but not the PX4 v1.16 release. ::: ## Read Before Upgrading @@ -40,22 +40,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 공통 -- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). - - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. - - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). -- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. - The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). -- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. - This makes log decryption much easier, as there is no need to download or identify a separate key file. - ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). -- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. - Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. - This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. - ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). -- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) -- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. - This typically reduces false warnings due to magnetometer inconsistencies. - ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). +- TBD ### 제어 @@ -71,26 +56,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 시뮬레이션 -- [SIH]: - - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. - ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). - - SIH now supports the standard VTOL airframe - ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). -- [Gazebo]: - - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. - The default installer scripts (used for CI) and documentation have been updated. - This is required because Garden end-of-life is Nov 2024. - ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) - - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). - - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). - - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). - - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). - - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). - - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). - - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) - - [Moving platform simulation](../sim_gazebo_gz/worlds#moving-platform) ([PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471)) +- TBD ### Ethernet @@ -98,7 +64,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 -- **[Feature]** [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113)) +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). ### MAVLink @@ -106,8 +72,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Multi-Rotor -- Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) -- Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507) +- TBD ### 수직이착륙기(VTOL) @@ -115,29 +80,11 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Fixed-wing -- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) +- TBD ### 탐사선 -This release contains a major rework for the rover support in PX4: - -- Complete restructure of the [rover related documentation](../frames_rover/index.md). -- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). -- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): - - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). -- New module dedicated to [differential rovers](../frames_rover/differential.md): - - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). -- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): - - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). -- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). - This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): - - Generic Differential Rover `50000`. - - Generic Ackermann Rover `51000`. - - Axial SCX10 2 Trail Honcho `51001`. - - Generic Mecanum Rover `52000`. -- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. -- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). -- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. +- TBD ### ROS 2 diff --git a/docs/ko/ros2/px4_ros2_control_interface.md b/docs/ko/ros2/px4_ros2_control_interface.md index 4c2d03a900..890858df38 100644 --- a/docs/ko/ros2/px4_ros2_control_interface.md +++ b/docs/ko/ros2/px4_ros2_control_interface.md @@ -345,7 +345,7 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: - [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -407,7 +407,7 @@ _goto_setpoint->update( #### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) - + :::info This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. @@ -549,7 +549,7 @@ If you want to control an actuator that does not control the vehicle's motion, b ### Controlling a VTOL - + To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: diff --git a/docs/ko/ros2/px4_ros2_msg_translation_node.md b/docs/ko/ros2/px4_ros2_msg_translation_node.md index 73aaade3b4..0bb22c79c1 100644 --- a/docs/ko/ros2/px4_ros2_msg_translation_node.md +++ b/docs/ko/ros2/px4_ros2_msg_translation_node.md @@ -1,6 +1,6 @@ # PX4 ROS 2 Message Translation Node - + The message translation node allows ROS 2 applications that were compiled against different versions of the PX4 messages to interwork with newer versions of PX4, and vice versa, without having to change either the application or the PX4 side. @@ -207,7 +207,7 @@ Message translations can be either _direct_ or _generic_. ### File Structure -Starting from PX4 v1.16 (main), the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: +Starting from PX4 v1.16, the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: ``` PX4-Autopilot diff --git a/docs/ko/ros2/user_guide.md b/docs/ko/ros2/user_guide.md index d267cadfbb..9cad98c9d7 100644 --- a/docs/ko/ros2/user_guide.md +++ b/docs/ko/ros2/user_guide.md @@ -34,7 +34,7 @@ The generator uses the uORB message definitions in the source tree: [PX4-Autopil ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases). -Starting from PX4 v1.16 (main) in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. +Starting from PX4 v1.16, in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. This requires the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to be running to ensure that messages can be converted and exchanged correctly. Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. @@ -378,7 +378,7 @@ accelerometer_integral_dt: 4739 #### (Optional) Starting the Translation Node - + This example is built with PX4 and ROS2 versions that use the same message definitions. If you were to use incompatible [message versions](../middleware/uorb.md#message-versioning) you would need to install and run the [Message Translation Node](./px4_ros2_msg_translation_node.md) as well, before running the example: diff --git a/docs/ko/sim_gazebo_gz/worlds.md b/docs/ko/sim_gazebo_gz/worlds.md index 7a57b8944a..a4a461753a 100644 --- a/docs/ko/sim_gazebo_gz/worlds.md +++ b/docs/ko/sim_gazebo_gz/worlds.md @@ -75,7 +75,7 @@ World with walls that is designed for testing [collision prevention](../computer ## Moving Platform - + [Empty world](#default) with the addition of a flat moving platform, to simulate drone operations from moving vehicles like ships or trucks. The platform is controlled by a plugin which is included in the world. The platform is at a height of 2m, so place the vehicle on it with: diff --git a/docs/ko/telemetry/jfi_telemetry.md b/docs/ko/telemetry/jfi_telemetry.md index f9c10669d5..9fbd07f31d 100644 --- a/docs/ko/telemetry/jfi_telemetry.md +++ b/docs/ko/telemetry/jfi_telemetry.md @@ -20,7 +20,7 @@ Operating in the 2.4GHz frequency band, it allows unrestricted global use withou - **Frequency Band:** 2.4GHz - **Speed:** Up to 11 Mbps (adjustable) -- **Range:** Up to 500 meters (varies upon environments) +- **Range:** Up to 1000 meters (varies upon environments) - **Payload Capacity:** Up to 1024 bytes ### Network Schemes From da39385544738c05a5166aba2a6495b48ad28116 Mon Sep 17 00:00:00 2001 From: Crowdin Bot Date: Sun, 8 Jun 2025 00:13:09 +0000 Subject: [PATCH 128/130] New Crowdin translations - uk --- docs/uk/SUMMARY.md | 6 +- docs/uk/dev_log/log_encryption.md | 2 +- docs/uk/flight_controller/kakuteh7-wing.md | 10 +- docs/uk/flight_modes_rover/ackermann.md | 2 +- docs/uk/flight_modes_rover/differential.md | 2 +- docs/uk/flight_modes_rover/mecanum.md | 2 +- docs/uk/frames_rover/ackermann.md | 2 +- docs/uk/frames_rover/differential.md | 2 +- docs/uk/frames_rover/mecanum.md | 2 +- docs/uk/mavlink/index.md | 89 +++++++ docs/uk/mavlink/protocols.md | 51 ++++ docs/uk/middleware/mavlink.md | 88 +------ docs/uk/middleware/uorb.md | 4 +- docs/uk/middleware/uxrce_dds.md | 5 +- docs/uk/releases/1.16.md | 221 ++++++++++++++++++ docs/uk/releases/index.md | 3 +- docs/uk/releases/main.md | 73 +----- docs/uk/ros2/px4_ros2_control_interface.md | 6 +- docs/uk/ros2/px4_ros2_msg_translation_node.md | 4 +- docs/uk/ros2/user_guide.md | 4 +- docs/uk/sim_gazebo_gz/worlds.md | 2 +- docs/uk/telemetry/jfi_telemetry.md | 2 +- 22 files changed, 404 insertions(+), 178 deletions(-) create mode 100644 docs/uk/mavlink/index.md create mode 100644 docs/uk/mavlink/protocols.md create mode 100644 docs/uk/releases/1.16.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index 86d0b93703..f6ec7e91fd 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -725,12 +725,13 @@ - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - - [Повідомлення MAVLink](middleware/mavlink.md) + - [MAVLink Messaging](mavlink/index.md) - [Adding Messages](mavlink/adding_messages.md) - [Streaming Messages](mavlink/streaming_messages.md) - [Receiving Messages](mavlink/receiving_messages.md) - [Custom MAVLink Messages](mavlink/custom_messages.md) - - [Standard Modes Protocol](mavlink/standard_modes.md) + - [Protocols/Microservices](mavlink/protocols.md) + - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [Модулі & Команди](modules/modules_main.md) - [Автоматичне підлаштування](modules/modules_autotune.md) @@ -860,6 +861,7 @@ - [Релізи](releases/index.md) - [main (alpha)](releases/main.md) + - [1.16 (release candidate)](releases/1.16.md) - [1.15 (stable)](releases/1.15.md) - [1.14](releases/1.14.md) - [1.13](releases/1.13.md) diff --git a/docs/uk/dev_log/log_encryption.md b/docs/uk/dev_log/log_encryption.md index 4685332e74..959d5ce491 100644 --- a/docs/uk/dev_log/log_encryption.md +++ b/docs/uk/dev_log/log_encryption.md @@ -12,7 +12,7 @@ To use it you will need to build firmware with this feature enabled and then upl ::: :::tip -Log encryption was has been improved in PX4 main (v1.16+) to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). +Log encryption was has been improved in PX4 v1.16 to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). In earlier versions the encrypted symmetric key was stored in a separate file. For more information see the [Log Encryption (PX4 v1.15)](https://docs.px4.io/v1.15/en/dev_log/log_encryption.html). diff --git a/docs/uk/flight_controller/kakuteh7-wing.md b/docs/uk/flight_controller/kakuteh7-wing.md index 2461dc41bf..bea7e564f5 100644 --- a/docs/uk/flight_controller/kakuteh7-wing.md +++ b/docs/uk/flight_controller/kakuteh7-wing.md @@ -1,4 +1,6 @@ -# Holybro Kakute H7 V2 +# Holybro Kakute H743-Wing + + :::warning PX4 не розробляє цей (або будь-який інший) автопілот. @@ -31,9 +33,7 @@ This flight controller is [manufacturer supported](../flight_controller/autopilo | Buz-, Buz+ | Piezo buzzer | | | M1 to M14 | Motor signal outputs | | - - -## Оновлення завантажувача PX4 +## PX4 Bootloader Update {#bootloader} The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki). Before the PX4 firmware can be installed, the _PX4 bootloader_ must be flashed. @@ -50,7 +50,7 @@ make holybro_kakuteh7-wing_default ## Встановлення прошивки PX4 :::info -KakuteH7-wing is supported with PX4 master & PX4 v1.16 or newer.. +KakuteH7-wing is supported in PX4 v1.16 or newer. До випуску вам потрібно буде вручну зібрати та встановити прошивку. ::: diff --git a/docs/uk/flight_modes_rover/ackermann.md b/docs/uk/flight_modes_rover/ackermann.md index a964aff934..844b92b528 100644 --- a/docs/uk/flight_modes_rover/ackermann.md +++ b/docs/uk/flight_modes_rover/ackermann.md @@ -137,7 +137,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | Команда | Опис | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------- | diff --git a/docs/uk/flight_modes_rover/differential.md b/docs/uk/flight_modes_rover/differential.md index 4639ea9995..bb94546119 100644 --- a/docs/uk/flight_modes_rover/differential.md +++ b/docs/uk/flight_modes_rover/differential.md @@ -115,7 +115,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | Команда | Опис | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ | diff --git a/docs/uk/flight_modes_rover/mecanum.md b/docs/uk/flight_modes_rover/mecanum.md index 1d0d89391a..67381327f5 100644 --- a/docs/uk/flight_modes_rover/mecanum.md +++ b/docs/uk/flight_modes_rover/mecanum.md @@ -140,7 +140,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | Команда | Опис | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ | diff --git a/docs/uk/frames_rover/ackermann.md b/docs/uk/frames_rover/ackermann.md index 80575a7ee9..3a8c1c191e 100644 --- a/docs/uk/frames_rover/ackermann.md +++ b/docs/uk/frames_rover/ackermann.md @@ -1,6 +1,6 @@ # Ackermann Rovers - + An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates. This kind of steering is used on most commercial vehicles, including cars, trucks etc. diff --git a/docs/uk/frames_rover/differential.md b/docs/uk/frames_rover/differential.md index a74fbd1d50..95ffe04993 100644 --- a/docs/uk/frames_rover/differential.md +++ b/docs/uk/frames_rover/differential.md @@ -1,6 +1,6 @@ # Differential Rovers - + A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate. Forward motion is achieved by driving both wheels at the same speed in the same direction. diff --git a/docs/uk/frames_rover/mecanum.md b/docs/uk/frames_rover/mecanum.md index 7d9a249156..548e7bcf4c 100644 --- a/docs/uk/frames_rover/mecanum.md +++ b/docs/uk/frames_rover/mecanum.md @@ -1,6 +1,6 @@ # Mecanum Rovers - + A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first. Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place. diff --git a/docs/uk/mavlink/index.md b/docs/uk/mavlink/index.md new file mode 100644 index 0000000000..3da14afef9 --- /dev/null +++ b/docs/uk/mavlink/index.md @@ -0,0 +1,89 @@ +# Повідомлення MAVLink + +[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. + +PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. + +Ця тема надає короткий огляд основних концепцій MAVLink, таких як повідомлення, команди та мікросервіси. +It also links instructions for how you can add PX4 support for: + +- [Adding Standard Messages](../mavlink/adding_messages.md) +- [Streaming MAVLink messages](../mavlink/streaming_messages.md) +- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) +- [Custom MAVLink Messages](../mavlink/custom_messages.md) +- [Protocols/Microservices](../mavlink/protocols.md) + +:::info +We do not yet cover _command_ handling and sending, or how to implement your own microservices. +::: + +## Огляд MAVLink + +MAVLink - це легкий протокол, який був розроблений для ефективної відправки повідомлень по ненадійним радіоканалах з низькою пропускною здатністю. + +_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. +Вони навмисно легкі, мають обмежений розмір і не мають семантики для повторного надсилання та підтвердження. +Окремі повідомлення зазвичай використовуються для потокової передачі телеметрії або інформації про стан, а також для надсилання команд, які не потребують підтвердження - наприклад, команд уставки, що надсилаються з високою швидкістю. + +[Microservices](../mavlink/protocols.md) are "meta protocols" built on top of MAVLink messages. +They are used to communicate information that cannot be sent in a single message. + +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) is a service for sending commands that may need acknowledgement and retransmission (quality of service). +Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. +The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. +The command is automatically resent a number of times if no acknowledgment is received. +Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. + +Others services include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html), [Parameter Protocol](https://mavlink.io/en/services/parameter.html), and [Mission Protocol](https://mavlink.io/en/services/mission.html). +For more information on what PX4 supports see [Microservices](../mavlink/protocols.md). + +MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). +Інструментарій MAVLink включає в себе генератори коду, які створюють з цих визначень специфічні для мови програмування бібліотеки для надсилання та отримання повідомлень. +Зверніть увагу, що більшість згенерованих бібліотек не створюють код для реалізації мікросервісів. + +The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): + +- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. + The definitions move to `common.xml` if accepted following testing. +- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. + Вони підтримуються багатьма польотними стеками, наземними станціями та периферійними пристроями MAVLink. + Польотні стеки, які використовують ці визначення, з більшою ймовірністю будуть взаємодіяти. +- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. + Вони присутні на переважній більшості польотних стеків і реалізовані однаково. +- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. + +The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. + +Протокол покладається на те, що кожна сторона комунікації має спільне визначення того, які повідомлення надсилаються. +Це означає, що для того, щоб взаємодіяти, обидва кінці комунікації повинні використовувати бібліотеки, створені на основі одного і того ж визначення XML. + + + +## PX4 та MAVLink + +PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. +In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. + +:::info +To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). +During development you can use definitions in `development.xml`. +You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. +::: + +PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). +This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). + +Інструментарій збірки генерує заголовні файли MAVLink 2 C під час збірки. +The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: + +- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). + You can change this to any other definition file, but the file must include `common.xml`. +- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). + +The files are generated into the build directory: `/build//mavlink/`. diff --git a/docs/uk/mavlink/protocols.md b/docs/uk/mavlink/protocols.md new file mode 100644 index 0000000000..d7808a61f1 --- /dev/null +++ b/docs/uk/mavlink/protocols.md @@ -0,0 +1,51 @@ +# MAVLink Microservices (Protocols) + +MAVLink "microservices" are a protocols that use multiple messages exchanged between components to communicate more complicated information. +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) provides an efficient mechanism for packaging a command in a (particular) message and receiving acknowledgement of the command in another message. + +MAVLink microservices are documented the [MAVLink Guide](https://mavlink.io/en/services/) (this is not exhaustive: not all messages are grouped into protocols and not all protocols are documented). + +This section lists the services known to be supported/not supported by PX4 in this version. + +## Supported Microservices + +These services are known to be supported in some form: + +- [Battery Protocol](https://mavlink.io/en/services/battery.html) + - [BATTERY_STATUS](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) and [BATTERY_INFO](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) are streamed. +- Camera Protocols + - [Camera Protocol v2](https://mavlink.io/en/services/camera.html) + - [Camera Definition](https://mavlink.io/en/services/camera_def.html) +- [Command Protocol](https://mavlink.io/en/services/command.html) +- [Component Metadata Protocol](https://mavlink.io/en/services/component_information.html) +- [Events Interface](https://mavlink.io/en/services/events.html) +- [File Transfer Protocol (FTP)](https://mavlink.io/en/services/ftp.html) +- Gimbal Protocols + - [Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html) + - Can be enabled by [Gimbal Configuration](../advanced/gimbal_control.md#mavlink-gimbal-mnt-mode-out-mavlink) + - PX4 an act as a MAVLink Gimbal for one FC-connected Gimbal +- [Heartbeat/Connection Protocol](https://mavlink.io/en/services/heartbeat.html) +- [High Latency Protocol](https://mavlink.io/en/services/high_latency.html) — PX4 streams [HIGH_LATENCY2](https://mavlink.io/en/messages/common.html#HIGH_LATENCY2) +- [Image Transmission Protocol](https://mavlink.io/en/services/image_transmission.html) +- [Landing Target Protocol](https://mavlink.io/en/services/landing_target.html) +- [Manual Control (Joystick) Protocol](https://mavlink.io/en/services/manual_control.html) +- [MAVLink Id Assignment (sysid, compid)](https://mavlink.io/en/services/mavlink_id_assignment.html) +- [Mission Protocol](https://mavlink.io/en/services/mission.html) +- [Offboard Control Protocol](https://mavlink.io/en/services/offboard_control.html) +- [Remote ID](../peripherals/remote_id.md) ([Open Drone ID Protocol](https://mavlink.io/en/services/opendroneid.html)) +- [Parameter Protocol](https://mavlink.io/en/services/parameter.html) +- [Parameter Protocol Extended](https://mavlink.io/en/services/parameter_ext.html) — Allows setting string parameters. Used for setting string parameters set in camera definition files. +- [Payload Protocol](https://mavlink.io/en/services/payload.html) +- [Ping Protocol](https://mavlink.io/en/services/ping.html) +- [Standard Modes Protocol](../mavlink/standard_modes.md) +- [Terrain Protocol](https://mavlink.io/en/services/terrain.html) +- [Time Synchronization](https://mavlink.io/en/services/timesync.html) +- [Traffic Management (UTM/ADS-B)](https://mavlink.io/en/services/traffic_management.html) +- [Arm Authorization Protocol](https://mavlink.io/en/services/arm_authorization.html) + +## Непідтримувано + +These services are not supported/used by PX4: + +- [Illuminator Protocol](https://mavlink.io/en/services/illuminator.html) +- [Tunnel Protocol](https://mavlink.io/en/services/tunnel.html) diff --git a/docs/uk/middleware/mavlink.md b/docs/uk/middleware/mavlink.md index cf35f57ea4..c88fc7840e 100644 --- a/docs/uk/middleware/mavlink.md +++ b/docs/uk/middleware/mavlink.md @@ -1,87 +1 @@ -# Повідомлення MAVLink - -[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. - -PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. - -Ця тема надає короткий огляд основних концепцій MAVLink, таких як повідомлення, команди та мікросервіси. -It also links instructions for how you can add PX4 support for: - -- [Adding Standard Messages](../mavlink/adding_messages.md) -- [Streaming MAVLink messages](../mavlink/streaming_messages.md) -- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) -- [Custom MAVLink Messages](../mavlink/custom_messages.md) - -:::info -We do not yet cover _command_ handling and sending, or how to implement your own microservices. -::: - -## Огляд MAVLink - -MAVLink - це легкий протокол, який був розроблений для ефективної відправки повідомлень по ненадійним радіоканалах з низькою пропускною здатністю. - -_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. -Вони навмисно легкі, мають обмежений розмір і не мають семантики для повторного надсилання та підтвердження. -Окремі повідомлення зазвичай використовуються для потокової передачі телеметрії або інформації про стан, а також для надсилання команд, які не потребують підтвердження - наприклад, команд уставки, що надсилаються з високою швидкістю. - -The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement. -Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. -The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. -Якщо команда не буде отримана, вона буде повторно надіслана автоматично. -Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. - -[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages. -Вони використовуються для передачі інформації, яку неможливо надіслати одним повідомленням, а також для забезпечення таких функцій, як надійний зв'язок. -Описаний вище командний протокол є одним з таких сервісів. -Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html). - -MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). -Інструментарій MAVLink включає в себе генератори коду, які створюють з цих визначень специфічні для мови програмування бібліотеки для надсилання та отримання повідомлень. -Зверніть увагу, що більшість згенерованих бібліотек не створюють код для реалізації мікросервісів. - -The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): - -- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. - The definitions move to `common.xml` if accepted following testing. -- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. - Вони підтримуються багатьма польотними стеками, наземними станціями та периферійними пристроями MAVLink. - Польотні стеки, які використовують ці визначення, з більшою ймовірністю будуть взаємодіяти. -- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. - Вони присутні на переважній більшості польотних стеків і реалізовані однаково. -- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. - -The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. - -Протокол покладається на те, що кожна сторона комунікації має спільне визначення того, які повідомлення надсилаються. -Це означає, що для того, щоб взаємодіяти, обидва кінці комунікації повинні використовувати бібліотеки, створені на основі одного і того ж визначення XML. - - - -## PX4 та MAVLink - -PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. -In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. - -:::info -To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). -During development you can use definitions in `development.xml`. -You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. -::: - -PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). -This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). - -Інструментарій збірки генерує заголовні файли MAVLink 2 C під час збірки. -The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: - -- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). - You can change this to any other definition file, but the file must include `common.xml`. -- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). - -The files are generated into the build directory: `/build//mavlink/`. + diff --git a/docs/uk/middleware/uorb.md b/docs/uk/middleware/uorb.md index ae387e9ac0..764a2bb908 100644 --- a/docs/uk/middleware/uorb.md +++ b/docs/uk/middleware/uorb.md @@ -116,9 +116,9 @@ As there are external tools using uORB messages from log files, such as [Flight ## Message Versioning - + -Optional message versioning was introduced in the `main` branch (planned for PX4 v1.16+) to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. +Optional message versioning was introduced PX4 v1.16 to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. Versioned messages are designed to remain more stable over time compared to their non-versioned counterparts, as they are intended to be used across multiple releases of PX4 and external systems, ensuring greater compatibility over longer periods. Versioned messages include an additional field `uint32 MESSAGE_VERSION = x`, where `x` corresponds to the current version of the message. diff --git a/docs/uk/middleware/uxrce_dds.md b/docs/uk/middleware/uxrce_dds.md index 6c545dbf6e..472f3f502a 100644 --- a/docs/uk/middleware/uxrce_dds.md +++ b/docs/uk/middleware/uxrce_dds.md @@ -430,16 +430,17 @@ publications: - topic: /fmu/out/collision_constraints type: px4_msgs::msg::CollisionConstraints + rate_limit: 50. # Limit max publication rate to 50 Hz ... - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry - rate_limit: 150. + # Use default publication rate limit of 100 Hz - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus - rate_limit: 50. + rate_limit: 5. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint diff --git a/docs/uk/releases/1.16.md b/docs/uk/releases/1.16.md new file mode 100644 index 0000000000..fdccee7900 --- /dev/null +++ b/docs/uk/releases/1.16.md @@ -0,0 +1,221 @@ +# PX4-Autopilot v1.16.0 Release Notes + + + + + +
    +
    +

    This page is on a release branch, and hence possibly out of date. See the latest version.

    +
    +
    + +This document covers all changes in PX4 v1.16.0 since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)). + +:::info +These notes include only changes merged in 2023 and later — commits before 2023 are not listed. +::: + +## Прочитайте перед оновленням + +Please continue reading for [upgrade instructions](#upgrade-guide). + +## Основні зміни + +- **Rover support rework** + - New dedicated firmware build for rovers (airframe IDs 50000–52000) + - Separate modules for Ackermann, differential and mecanum rovers, each with manual, acro, stabilized, position and auto modes + - Shared pure-pursuit guidance library for all rover modules + - Legacy rover position control module deprecated in favor of the new modules + +## Інструкції для оновлення + +- [PX4-Autopilot#24648](https://github.com/PX4/PX4-Autopilot/pull/24648): Added setting default for EKF2_EV_CTRL to 15 for VOXL 2 boards +- [PX4-Autopilot#22517](https://github.com/PX4/PX4-Autopilot/pull/22517): Change default ethernet IP +- [PX4-Autopilot#24602](https://github.com/PX4/PX4-Autopilot/pull/24602): remove serial port default from sf45 module + +## Інші зміни + +### Підтримка обладнання + +- **[New Hardware]** [PX4-Autopilot#23830](https://github.com/PX4/PX4-Autopilot/pull/23830): Boards: ARK FPV FC +- **[New Hardware]** [PX4-Autopilot#23414](https://github.com/PX4/PX4-Autopilot/pull/23414): board: add cuav 7-nano +- **[New Hardware]** [PX4-Autopilot#24769](https://github.com/PX4/PX4-Autopilot/pull/24769): add new board corvon743v1 +- **[New Hardware]** [PX4-Autopilot#24018](https://github.com/PX4/PX4-Autopilot/pull/24018): boards: bluerobotics: navigator: Add initial support +- **[New Hardware]** [PX4-Autopilot#24147](https://github.com/PX4/PX4-Autopilot/pull/24147): boards: add new board micoair743-v2 +- **[New Hardware]** [PX4-Autopilot#23218](https://github.com/PX4/PX4-Autopilot/pull/23218): boards: add new board micoair h743 +- **[New Hardware]** [PX4-Autopilot#24512](https://github.com/PX4/PX4-Autopilot/pull/24512): boards: Add FMUv6s target +- **[New Hardware]** [PX4-Autopilot#23927](https://github.com/PX4/PX4-Autopilot/pull/23927): manifest: Add Skynode S baseboard +- **[New Hardware]** [PX4-Autopilot#23257](https://github.com/PX4/PX4-Autopilot/pull/23257): Add Tropic VMU board support (Baseboard for Teensy 4.1) +- **[New Hardware]** [PX4-Autopilot#23697](https://github.com/PX4/PX4-Autopilot/pull/23697): boards: add new board X-MAV AP-H743v2 +- **[New Hardware]** [PX4-Autopilot#23551](https://github.com/PX4/PX4-Autopilot/pull/23551): 3DR boards: Support for 3DR Control Zero H7 OEM Rev G +- **[New Hardware]** [PX4-Autopilot#23623](https://github.com/PX4/PX4-Autopilot/pull/23623): new board support ZeroOne x6 + +### Загальні + +- [Optical flow scaling factor - SENS_FLOW_SCALE](../sensor/optical_flow.md#scale-factor). ([PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936)). + +- [PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813): Reintroduce optional parameter versioning mechanism for airframe maintainers + +- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). + - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. + - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). + +- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. + The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). + +- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. + This makes log decryption much easier, as there is no need to download or identify a separate key file. + ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). + +- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. + Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. + This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. + ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). + +- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) + +- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. + This typically reduces false warnings due to magnetometer inconsistencies. + ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). + +### Управління + +- [PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863): [Sponsored by ARK] Bidirectional DShot + +- [PX4-Autopilot#24196](https://github.com/PX4/PX4-Autopilot/pull/24196): Make control allocation and actuator effectiveness a non-module-specific library + +- [PX4-Autopilot#24221](https://github.com/PX4/PX4-Autopilot/pull/24221): Spacecraft Build and Bare Control Allocator + +- Configurable multicopter orbit-mode yaw via `MC_ORBIT_YAW_MOD` ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) + +- Collision prevention now works in manual (acceleration-based) flight mode (`MPC_POS_MODE`) ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507)) + +### Оцінки + +- [PX4-Autopilot#23854](https://github.com/PX4/PX4-Autopilot/pull/23854): EKF2: ellipsoidal earth navigation + +- [PX4-Autopilot#23263](https://github.com/PX4/PX4-Autopilot/pull/23263): EKF2: Terrain state + +- [PX4-Autopilot#23185](https://github.com/PX4/PX4-Autopilot/pull/23185): ekf2: add mag type init + +- [PX4-Autopilot#23436](https://github.com/PX4/PX4-Autopilot/pull/23436): ekf2: Optical flow enabled by default + +- Position-loss failsafe delay removed; triggers 1 s after loss (see Common) + +### Датчики + +- [PX4-Autopilot#23656](https://github.com/PX4/PX4-Autopilot/pull/23656): Implemented AUAV absolute/differential pressure sensor support + +- [PX4-Autopilot#23639](https://github.com/PX4/PX4-Autopilot/pull/23639): Implemented temperature sensor support for INA228 / INA238 + +- [PX4-Autopilot#22744](https://github.com/PX4/PX4-Autopilot/pull/22744): Add Ublox ZED-F9P-15B + +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Mag cal: automatically disable internal mags if external ones are available + +- [PX4-Autopilot#23064](https://github.com/PX4/PX4-Autopilot/pull/23064): BMP581: Add Bosch BMP581 barometer + +- [PX4-Autopilot#22914](https://github.com/PX4/PX4-Autopilot/pull/22914): Murata SCH16T IMU driver + +- [PX4-Autopilot#23023](https://github.com/PX4/PX4-Autopilot/pull/23023): ST IIS2MDC Magnetometer driver + +- [PX4-Autopilot#24121](https://github.com/PX4/PX4-Autopilot/pull/24121): Include distance sensor in dds topics + +- [PX4-Autopilot#23925](https://github.com/PX4/PX4-Autopilot/pull/23925): drivers: magnetometer: mmc5983ma: Add SPI support + +- [PX4-Autopilot#23909](https://github.com/PX4/PX4-Autopilot/pull/23909): drivers/magnetometer/ak09916: Add support to AK09915 + +- [PX4-Autopilot#23362](https://github.com/PX4/PX4-Autopilot/pull/23362): Add Bosch BMM350 magnetometer + +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Compass calibration now disables internal compass when external unit present, reducing false warnings + +### Симуляція + +- **SIH**: + - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. + ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). + - SIH now supports the standard VTOL airframe + ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). +- **Gazebo**: + - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. + The default installer scripts (used for CI) and documentation have been updated. + This is required because Garden end-of-life is Nov 2024. + ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) + - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). + - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). + - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). + - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). + - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). + - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). + - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) + - [PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471): Gazebo: Moving platform + +### uXRCE-DDS / ROS2 + +- **[Feature]** [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically +- [PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582): dds_topics: add vtol_vehicle_status +- [PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583): dds_topics: add home_position + +### MAVLink + +- Уточнюється + +### Мульти-Ротор + +- [PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173): [Multirotor] add yaw torque low pass filter + +- [PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943): Add gz model for quadtailsitter + +- [PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358): Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) + +- [PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507): Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). + +### VTOL + +- Уточнюється + +### Літак з фіксованим крилом + +- [PX4-Autopilot#24167](https://github.com/PX4/PX4-Autopilot/pull/24167): Fixedwing: fix wheel controller + +- [PX4-Autopilot#23520](https://github.com/PX4/PX4-Autopilot/pull/23520): FixedWing: allow position control without valid global position + +- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) + +### Ровер + +This release contains a major rework for the rover support in PX4: + +- Complete restructure of the [rover related documentation](../frames_rover/index.md). +- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). +- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): + - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). +- New module dedicated to [differential rovers](../frames_rover/differential.md): + - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). +- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): + - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). +- Added rover-specific firmware build (`50000–52000`) for Ackermann, differential and mecanum rovers +- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). + This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): + - Generic Differential Rover `50000`. + - Generic Ackermann Rover `51000`. + - Axial SCX10 2 Trail Honcho `51001`. + - Generic Mecanum Rover `52000`. +- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. +- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). +- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. + +### Infrastructure + +- [PX4-Autopilot#24011](https://github.com/PX4/PX4-Autopilot/pull/24011): standard_modes: add vehicle-type specific standard modes +- [PX4-Autopilot#24020](https://github.com/PX4/PX4-Autopilot/pull/24020): ci: build all upload to releases +- [PX4-Autopilot#24002](https://github.com/PX4/PX4-Autopilot/pull/24002): ci: px4-dev container +- [PX4-Autopilot#23937](https://github.com/PX4/PX4-Autopilot/pull/23937): ci: workflow for ubuntu 24 +- [PX4-Autopilot#23869](https://github.com/PX4/PX4-Autopilot/pull/23869): ci: add test for Ubuntu 22.04 +- [PX4-Autopilot#23574](https://github.com/PX4/PX4-Autopilot/pull/23574): ci: try runs-on Dronecode Infra +- [PX4-Autopilot#23550](https://github.com/PX4/PX4-Autopilot/pull/23550): ci: replace build workflows diff --git a/docs/uk/releases/index.md b/docs/uk/releases/index.md index f08b5351cc..32ee1a8d77 100644 --- a/docs/uk/releases/index.md +++ b/docs/uk/releases/index.md @@ -2,7 +2,8 @@ Перелік PX4 реліз, вони містять список змін, що відбулися в кожному релізі, пояснення включених функцій, виправлень, застарілих та оновлень. -- [main](../releases/main.md) (changes since v1.15) +- [main](../releases/main.md) (changes since v1.16) +- [v1.16](../releases/1.16.md) - [v1.15](../releases/1.15.md) - [v1.14](../releases/1.14.md) - [v1.13](../releases/1.13.md) diff --git a/docs/uk/releases/main.md b/docs/uk/releases/main.md index 9003f6a93d..b51219ded8 100644 --- a/docs/uk/releases/main.md +++ b/docs/uk/releases/main.md @@ -9,15 +9,15 @@ const { site } = useData();
    -

    This page is on a release bramch, and hence probably out of date. See the latest version.

    +

    This page is on a release branch, and hence probably out of date. See the latest version.

    -This contains changes to PX4 `main` branch since the last major release ([PX v1.15](../releases/1.15.md)). +This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)). :::warning -The PX4 v1.15 release is in beta testing, pending release. -Update these notes with features that are going to be in `main` but not the PX4 v1.15 release. +PX4 v1.16 is in candidate-release testing, pending release. +Update these notes with features that are going to be in `main` but not the PX4 v1.16 release. ::: ## Прочитайте перед оновленням @@ -40,22 +40,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Загальні -- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). - - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. - - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). -- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. - The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). -- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. - This makes log decryption much easier, as there is no need to download or identify a separate key file. - ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). -- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. - Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. - This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. - ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). -- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) -- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. - This typically reduces false warnings due to magnetometer inconsistencies. - ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). +- Уточнюється ### Управління @@ -71,26 +56,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Симуляція -- [SIH]: - - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. - ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). - - SIH now supports the standard VTOL airframe - ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). -- [Gazebo]: - - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. - The default installer scripts (used for CI) and documentation have been updated. - This is required because Garden end-of-life is Nov 2024. - ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) - - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). - - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). - - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). - - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). - - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). - - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). - - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) - - [Moving platform simulation](../sim_gazebo_gz/worlds#moving-platform) ([PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471)) +- Уточнюється ### Ethernet @@ -98,7 +64,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 -- **[Feature]** [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113)) +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). ### MAVLink @@ -106,8 +72,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Мульти-Ротор -- Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) -- Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507) +- Уточнюється ### VTOL @@ -115,29 +80,11 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Літак з фіксованим крилом -- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) +- Уточнюється ### Ровер -This release contains a major rework for the rover support in PX4: - -- Complete restructure of the [rover related documentation](../frames_rover/index.md). -- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). -- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): - - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). -- New module dedicated to [differential rovers](../frames_rover/differential.md): - - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). -- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): - - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). -- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). - This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): - - Generic Differential Rover `50000`. - - Generic Ackermann Rover `51000`. - - Axial SCX10 2 Trail Honcho `51001`. - - Generic Mecanum Rover `52000`. -- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. -- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). -- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. +- Уточнюється ### ROS 2 diff --git a/docs/uk/ros2/px4_ros2_control_interface.md b/docs/uk/ros2/px4_ros2_control_interface.md index 471d316906..8c3fb9e5f6 100644 --- a/docs/uk/ros2/px4_ros2_control_interface.md +++ b/docs/uk/ros2/px4_ros2_control_interface.md @@ -346,7 +346,7 @@ private: Наступні розділи надають список підтримуваних типів установок: - GotoSetpointType: Плавне позиціонування та (за бажанням) керування курсом -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - DirectActuatorsSetpointType: Пряме керування моторами та установками сервоприводів польотних поверхонь :::tip @@ -408,7 +408,7 @@ _goto_setpoint->update( #### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) - + :::info This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. @@ -550,7 +550,7 @@ and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). ### Controlling a VTOL - + To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: diff --git a/docs/uk/ros2/px4_ros2_msg_translation_node.md b/docs/uk/ros2/px4_ros2_msg_translation_node.md index da893b4ec6..7ad1c15295 100644 --- a/docs/uk/ros2/px4_ros2_msg_translation_node.md +++ b/docs/uk/ros2/px4_ros2_msg_translation_node.md @@ -1,6 +1,6 @@ # PX4 ROS 2 Message Translation Node - + The message translation node allows ROS 2 applications that were compiled against different versions of the PX4 messages to interwork with newer versions of PX4, and vice versa, without having to change either the application or the PX4 side. @@ -207,7 +207,7 @@ Message translations can be either _direct_ or _generic_. ### File Structure -Starting from PX4 v1.16 (main), the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: +Starting from PX4 v1.16, the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: ``` PX4-Autopilot diff --git a/docs/uk/ros2/user_guide.md b/docs/uk/ros2/user_guide.md index dd8d249474..ffbf192a6f 100644 --- a/docs/uk/ros2/user_guide.md +++ b/docs/uk/ros2/user_guide.md @@ -34,7 +34,7 @@ The generator uses the uORB message definitions in the source tree: [PX4-Autopil ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases). -Starting from PX4 v1.16 (main) in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. +Starting from PX4 v1.16, in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. This requires the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to be running to ensure that messages can be converted and exchanged correctly. Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. @@ -378,7 +378,7 @@ accelerometer_integral_dt: 4739 #### (Optional) Starting the Translation Node - + This example is built with PX4 and ROS2 versions that use the same message definitions. If you were to use incompatible [message versions](../middleware/uorb.md#message-versioning) you would need to install and run the [Message Translation Node](./px4_ros2_msg_translation_node.md) as well, before running the example: diff --git a/docs/uk/sim_gazebo_gz/worlds.md b/docs/uk/sim_gazebo_gz/worlds.md index ea3042666d..bb79e6faaa 100644 --- a/docs/uk/sim_gazebo_gz/worlds.md +++ b/docs/uk/sim_gazebo_gz/worlds.md @@ -75,7 +75,7 @@ World with walls that is designed for testing [collision prevention](../computer ## Moving Platform - + [Empty world](#default) with the addition of a flat moving platform, to simulate drone operations from moving vehicles like ships or trucks. The platform is controlled by a plugin which is included in the world. The platform is at a height of 2m, so place the vehicle on it with: diff --git a/docs/uk/telemetry/jfi_telemetry.md b/docs/uk/telemetry/jfi_telemetry.md index f1a5b1951c..decce61a0d 100644 --- a/docs/uk/telemetry/jfi_telemetry.md +++ b/docs/uk/telemetry/jfi_telemetry.md @@ -20,7 +20,7 @@ Operating in the 2.4GHz frequency band, it allows unrestricted global use withou - **Frequency Band:** 2.4GHz - **Speed:** Up to 11 Mbps (adjustable) -- **Range:** Up to 500 meters (varies upon environments) +- **Range:** Up to 1000 meters (varies upon environments) - **Payload Capacity:** Up to 1024 bytes ### Network Schemes From 9a2a8d4d3cf3bc74956337d8da8d506073684be0 Mon Sep 17 00:00:00 2001 From: Crowdin Bot Date: Sun, 8 Jun 2025 00:14:56 +0000 Subject: [PATCH 129/130] New Crowdin translations - zh-CN --- docs/zh/SUMMARY.md | 6 +- docs/zh/dev_log/log_encryption.md | 2 +- docs/zh/flight_controller/kakuteh7-wing.md | 10 +- docs/zh/flight_modes_rover/ackermann.md | 2 +- docs/zh/flight_modes_rover/differential.md | 2 +- docs/zh/flight_modes_rover/mecanum.md | 2 +- docs/zh/frames_rover/ackermann.md | 2 +- docs/zh/frames_rover/differential.md | 2 +- docs/zh/frames_rover/mecanum.md | 2 +- docs/zh/mavlink/index.md | 89 +++++++ docs/zh/mavlink/protocols.md | 51 ++++ docs/zh/middleware/mavlink.md | 88 +------ docs/zh/middleware/uorb.md | 4 +- docs/zh/middleware/uxrce_dds.md | 5 +- docs/zh/releases/1.16.md | 221 ++++++++++++++++++ docs/zh/releases/index.md | 3 +- docs/zh/releases/main.md | 73 +----- docs/zh/ros2/px4_ros2_control_interface.md | 6 +- docs/zh/ros2/px4_ros2_msg_translation_node.md | 4 +- docs/zh/ros2/user_guide.md | 4 +- docs/zh/sim_gazebo_gz/worlds.md | 2 +- docs/zh/telemetry/jfi_telemetry.md | 2 +- 22 files changed, 404 insertions(+), 178 deletions(-) create mode 100644 docs/zh/mavlink/index.md create mode 100644 docs/zh/mavlink/protocols.md create mode 100644 docs/zh/releases/1.16.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index fea7e0aed3..445e68f7e4 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -725,12 +725,13 @@ - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - - [MAVLink通讯](middleware/mavlink.md) + - [MAVLink Messaging](mavlink/index.md) - [Adding Messages](mavlink/adding_messages.md) - [Streaming Messages](mavlink/streaming_messages.md) - [Receiving Messages](mavlink/receiving_messages.md) - [Custom MAVLink Messages](mavlink/custom_messages.md) - - [Standard Modes Protocol](mavlink/standard_modes.md) + - [Protocols/Microservices](mavlink/protocols.md) + - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [模块 & 命令](modules/modules_main.md) - [自动调参](modules/modules_autotune.md) @@ -860,6 +861,7 @@ - [版本发布](releases/index.md) - [main (alpha)](releases/main.md) + - [1.16 (release candidate)](releases/1.16.md) - [1.15 (stable)](releases/1.15.md) - [1.14](releases/1.14.md) - [1.13](releases/1.13.md) diff --git a/docs/zh/dev_log/log_encryption.md b/docs/zh/dev_log/log_encryption.md index c8c4258e9b..f8783e32ef 100644 --- a/docs/zh/dev_log/log_encryption.md +++ b/docs/zh/dev_log/log_encryption.md @@ -12,7 +12,7 @@ To use it you will need to build firmware with this feature enabled and then upl ::: :::tip -Log encryption was has been improved in PX4 main (v1.16+) to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). +Log encryption was has been improved in PX4 v1.16 to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key). In earlier versions the encrypted symmetric key was stored in a separate file. For more information see the [Log Encryption (PX4 v1.15)](https://docs.px4.io/v1.15/en/dev_log/log_encryption.html). diff --git a/docs/zh/flight_controller/kakuteh7-wing.md b/docs/zh/flight_controller/kakuteh7-wing.md index 396320b787..e426a8aabe 100644 --- a/docs/zh/flight_controller/kakuteh7-wing.md +++ b/docs/zh/flight_controller/kakuteh7-wing.md @@ -1,4 +1,6 @@ -# Holybro Kakute H7 V2 +# Holybro Kakute H743-Wing + + :::warning PX4 does not manufacture this (or any) autopilot. @@ -31,9 +33,7 @@ The board can be bought from one of the following shops (for example): | Buz-, Buz+ | Piezo buzzer | | | M1 to M14 | Motor signal outputs | | - - -## PX4 Bootloader Update +## PX4 Bootloader Update {#bootloader} The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki). Before the PX4 firmware can be installed, the _PX4 bootloader_ must be flashed. @@ -50,7 +50,7 @@ make holybro_kakuteh7-wing_default ## Installing PX4 Firmware :::info -KakuteH7-wing is supported with PX4 master & PX4 v1.16 or newer.. +KakuteH7-wing is supported in PX4 v1.16 or newer. Prior to that release you will need to manually build and install the firmware. ::: diff --git a/docs/zh/flight_modes_rover/ackermann.md b/docs/zh/flight_modes_rover/ackermann.md index b28ed4531b..a46e229df9 100644 --- a/docs/zh/flight_modes_rover/ackermann.md +++ b/docs/zh/flight_modes_rover/ackermann.md @@ -137,7 +137,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | 通信 | 描述 | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------- | diff --git a/docs/zh/flight_modes_rover/differential.md b/docs/zh/flight_modes_rover/differential.md index 365f2cd851..f28a239af0 100644 --- a/docs/zh/flight_modes_rover/differential.md +++ b/docs/zh/flight_modes_rover/differential.md @@ -115,7 +115,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | 通信 | 描述 | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ | diff --git a/docs/zh/flight_modes_rover/mecanum.md b/docs/zh/flight_modes_rover/mecanum.md index 44f1073ab4..924dd7b55b 100644 --- a/docs/zh/flight_modes_rover/mecanum.md +++ b/docs/zh/flight_modes_rover/mecanum.md @@ -140,7 +140,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS #### Mission commands -The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`): +The following commands can be used in missions at time of writing (PX4 v1.16): | QGC mission item | 通信 | 描述 | | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ | diff --git a/docs/zh/frames_rover/ackermann.md b/docs/zh/frames_rover/ackermann.md index 80575a7ee9..3a8c1c191e 100644 --- a/docs/zh/frames_rover/ackermann.md +++ b/docs/zh/frames_rover/ackermann.md @@ -1,6 +1,6 @@ # Ackermann Rovers - + An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates. This kind of steering is used on most commercial vehicles, including cars, trucks etc. diff --git a/docs/zh/frames_rover/differential.md b/docs/zh/frames_rover/differential.md index a74fbd1d50..95ffe04993 100644 --- a/docs/zh/frames_rover/differential.md +++ b/docs/zh/frames_rover/differential.md @@ -1,6 +1,6 @@ # Differential Rovers - + A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate. Forward motion is achieved by driving both wheels at the same speed in the same direction. diff --git a/docs/zh/frames_rover/mecanum.md b/docs/zh/frames_rover/mecanum.md index 7d9a249156..548e7bcf4c 100644 --- a/docs/zh/frames_rover/mecanum.md +++ b/docs/zh/frames_rover/mecanum.md @@ -1,6 +1,6 @@ # Mecanum Rovers - + A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first. Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place. diff --git a/docs/zh/mavlink/index.md b/docs/zh/mavlink/index.md new file mode 100644 index 0000000000..f63038018f --- /dev/null +++ b/docs/zh/mavlink/index.md @@ -0,0 +1,89 @@ +# MAVLink通讯 + +[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. + +PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. + +This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices. +It also links instructions for how you can add PX4 support for: + +- [Adding Standard Messages](../mavlink/adding_messages.md) +- [Streaming MAVLink messages](../mavlink/streaming_messages.md) +- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) +- [Custom MAVLink Messages](../mavlink/custom_messages.md) +- [Protocols/Microservices](../mavlink/protocols.md) + +:::info +We do not yet cover _command_ handling and sending, or how to implement your own microservices. +::: + +## MAVLink Overview + +MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links. + +_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. +They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. +Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. + +[Microservices](../mavlink/protocols.md) are "meta protocols" built on top of MAVLink messages. +They are used to communicate information that cannot be sent in a single message. + +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) is a service for sending commands that may need acknowledgement and retransmission (quality of service). +Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. +The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. +The command is automatically resent a number of times if no acknowledgment is received. +Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. + +Others services include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html), [Parameter Protocol](https://mavlink.io/en/services/parameter.html), and [Mission Protocol](https://mavlink.io/en/services/mission.html). +For more information on what PX4 supports see [Microservices](../mavlink/protocols.md). + +MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). +The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages. +Note that most generated libraries do not create code to implement microservices. + +The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): + +- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. + The definitions move to `common.xml` if accepted following testing. +- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. + These are supported by many flight stacks, ground stations, and MAVLink peripherals. + Flight stacks that use these definitions are more likely to interoperate. +- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. + They are present on the vast majority of flight stacks and implemented in the same way. +- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. + +The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. + +The protocol relies on each end of the communication having a shared definition of what messages are being sent. +What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition. + + + +## PX4 and MAVLink + +PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. +In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. + +:::info +To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). +During development you can use definitions in `development.xml`. +You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. +::: + +PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). +This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). + +The build toolchain generates the MAVLink 2 C header files at build time. +The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: + +- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). + You can change this to any other definition file, but the file must include `common.xml`. +- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). + +The files are generated into the build directory: `/build//mavlink/`. diff --git a/docs/zh/mavlink/protocols.md b/docs/zh/mavlink/protocols.md new file mode 100644 index 0000000000..9dac078fb9 --- /dev/null +++ b/docs/zh/mavlink/protocols.md @@ -0,0 +1,51 @@ +# MAVLink Microservices (Protocols) + +MAVLink "microservices" are a protocols that use multiple messages exchanged between components to communicate more complicated information. +For example, the [Command Protocol](https://mavlink.io/en/services/command.html) provides an efficient mechanism for packaging a command in a (particular) message and receiving acknowledgement of the command in another message. + +MAVLink microservices are documented the [MAVLink Guide](https://mavlink.io/en/services/) (this is not exhaustive: not all messages are grouped into protocols and not all protocols are documented). + +This section lists the services known to be supported/not supported by PX4 in this version. + +## Supported Microservices + +These services are known to be supported in some form: + +- [Battery Protocol](https://mavlink.io/en/services/battery.html) + - [BATTERY_STATUS](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) and [BATTERY_INFO](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) are streamed. +- Camera Protocols + - [Camera Protocol v2](https://mavlink.io/en/services/camera.html) + - [Camera Definition](https://mavlink.io/en/services/camera_def.html) +- [Command Protocol](https://mavlink.io/en/services/command.html) +- [Component Metadata Protocol](https://mavlink.io/en/services/component_information.html) +- [Events Interface](https://mavlink.io/en/services/events.html) +- [File Transfer Protocol (FTP)](https://mavlink.io/en/services/ftp.html) +- Gimbal Protocols + - [Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html) + - Can be enabled by [Gimbal Configuration](../advanced/gimbal_control.md#mavlink-gimbal-mnt-mode-out-mavlink) + - PX4 an act as a MAVLink Gimbal for one FC-connected Gimbal +- [Heartbeat/Connection Protocol](https://mavlink.io/en/services/heartbeat.html) +- [High Latency Protocol](https://mavlink.io/en/services/high_latency.html) — PX4 streams [HIGH_LATENCY2](https://mavlink.io/en/messages/common.html#HIGH_LATENCY2) +- [Image Transmission Protocol](https://mavlink.io/en/services/image_transmission.html) +- [Landing Target Protocol](https://mavlink.io/en/services/landing_target.html) +- [Manual Control (Joystick) Protocol](https://mavlink.io/en/services/manual_control.html) +- [MAVLink Id Assignment (sysid, compid)](https://mavlink.io/en/services/mavlink_id_assignment.html) +- [Mission Protocol](https://mavlink.io/en/services/mission.html) +- [Offboard Control Protocol](https://mavlink.io/en/services/offboard_control.html) +- [Remote ID](../peripherals/remote_id.md) ([Open Drone ID Protocol](https://mavlink.io/en/services/opendroneid.html)) +- [Parameter Protocol](https://mavlink.io/en/services/parameter.html) +- [Parameter Protocol Extended](https://mavlink.io/en/services/parameter_ext.html) — Allows setting string parameters. Used for setting string parameters set in camera definition files. +- [Payload Protocol](https://mavlink.io/en/services/payload.html) +- [Ping Protocol](https://mavlink.io/en/services/ping.html) +- [Standard Modes Protocol](../mavlink/standard_modes.md) +- [Terrain Protocol](https://mavlink.io/en/services/terrain.html) +- [Time Synchronization](https://mavlink.io/en/services/timesync.html) +- [Traffic Management (UTM/ADS-B)](https://mavlink.io/en/services/traffic_management.html) +- [Arm Authorization Protocol](https://mavlink.io/en/services/arm_authorization.html) + +## Unsupported + +These services are not supported/used by PX4: + +- [Illuminator Protocol](https://mavlink.io/en/services/illuminator.html) +- [Tunnel Protocol](https://mavlink.io/en/services/tunnel.html) diff --git a/docs/zh/middleware/mavlink.md b/docs/zh/middleware/mavlink.md index 9555828822..c88fc7840e 100644 --- a/docs/zh/middleware/mavlink.md +++ b/docs/zh/middleware/mavlink.md @@ -1,87 +1 @@ -# MAVLink通讯 - -[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem. - -PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on. - -This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices. -It also links instructions for how you can add PX4 support for: - -- [Adding Standard Messages](../mavlink/adding_messages.md) -- [Streaming MAVLink messages](../mavlink/streaming_messages.md) -- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md) -- [Custom MAVLink Messages](../mavlink/custom_messages.md) - -:::info -We do not yet cover _command_ handling and sending, or how to implement your own microservices. -::: - -## MAVLink Overview - -MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links. - -_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data. -They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement. -Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate. - -The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement. -Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values. -The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`. -The command is resent automatically if no acknowledgment is received. -Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4. - -[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages. -They are used to communicate information that cannot be sent in a single message, and to deliver features such as reliable communication. -The command protocol described above is one such service. -Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html). - -MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html). -The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages. -Note that most generated libraries do not create code to implement microservices. - -The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them): - -- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard. - The definitions move to `common.xml` if accepted following testing. -- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases. - These are supported by many flight stacks, ground stations, and MAVLink peripherals. - Flight stacks that use these definitions are more likely to interoperate. -- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard. - They are present on the vast majority of flight stacks and implemented in the same way. -- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation. - -The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder. - -The protocol relies on each end of the communication having a shared definition of what messages are being sent. -What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition. - - - -## PX4 and MAVLink - -PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras. -In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards. - -:::info -To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`). -During development you can use definitions in `development.xml`. -You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions. -::: - -PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink). -This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/). - -The build toolchain generates the MAVLink 2 C header files at build time. -The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`: - -- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36). - You can change this to any other definition file, but the file must include `common.xml`. -- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)). - -The files are generated into the build directory: `/build//mavlink/`. + diff --git a/docs/zh/middleware/uorb.md b/docs/zh/middleware/uorb.md index 45a8ccf0b9..6cc75e15ff 100644 --- a/docs/zh/middleware/uorb.md +++ b/docs/zh/middleware/uorb.md @@ -116,9 +116,9 @@ As there are external tools using uORB messages from log files, such as [Flight ## Message Versioning - + -Optional message versioning was introduced in the `main` branch (planned for PX4 v1.16+) to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. +Optional message versioning was introduced PX4 v1.16 to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions. Versioned messages are designed to remain more stable over time compared to their non-versioned counterparts, as they are intended to be used across multiple releases of PX4 and external systems, ensuring greater compatibility over longer periods. Versioned messages include an additional field `uint32 MESSAGE_VERSION = x`, where `x` corresponds to the current version of the message. diff --git a/docs/zh/middleware/uxrce_dds.md b/docs/zh/middleware/uxrce_dds.md index c7814ed3fb..552f603cd1 100644 --- a/docs/zh/middleware/uxrce_dds.md +++ b/docs/zh/middleware/uxrce_dds.md @@ -430,16 +430,17 @@ publications: - topic: /fmu/out/collision_constraints type: px4_msgs::msg::CollisionConstraints + rate_limit: 50. # Limit max publication rate to 50 Hz ... - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry - rate_limit: 150. + # Use default publication rate limit of 100 Hz - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus - rate_limit: 50. + rate_limit: 5. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint diff --git a/docs/zh/releases/1.16.md b/docs/zh/releases/1.16.md new file mode 100644 index 0000000000..a3025b7556 --- /dev/null +++ b/docs/zh/releases/1.16.md @@ -0,0 +1,221 @@ +# PX4-Autopilot v1.16.0 Release Notes + + + + + +
    +
    +

    This page is on a release branch, and hence possibly out of date. See the latest version.

    +
    +
    + +This document covers all changes in PX4 v1.16.0 since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)). + +:::info +These notes include only changes merged in 2023 and later — commits before 2023 are not listed. +::: + +## Read Before Upgrading + +Please continue reading for [upgrade instructions](#upgrade-guide). + +## Major Changes + +- **Rover support rework** + - New dedicated firmware build for rovers (airframe IDs 50000–52000) + - Separate modules for Ackermann, differential and mecanum rovers, each with manual, acro, stabilized, position and auto modes + - Shared pure-pursuit guidance library for all rover modules + - Legacy rover position control module deprecated in favor of the new modules + +## Upgrade Guide + +- [PX4-Autopilot#24648](https://github.com/PX4/PX4-Autopilot/pull/24648): Added setting default for EKF2_EV_CTRL to 15 for VOXL 2 boards +- [PX4-Autopilot#22517](https://github.com/PX4/PX4-Autopilot/pull/22517): Change default ethernet IP +- [PX4-Autopilot#24602](https://github.com/PX4/PX4-Autopilot/pull/24602): remove serial port default from sf45 module + +## Other changes + +### Hardware Support + +- **[New Hardware]** [PX4-Autopilot#23830](https://github.com/PX4/PX4-Autopilot/pull/23830): Boards: ARK FPV FC +- **[New Hardware]** [PX4-Autopilot#23414](https://github.com/PX4/PX4-Autopilot/pull/23414): board: add cuav 7-nano +- **[New Hardware]** [PX4-Autopilot#24769](https://github.com/PX4/PX4-Autopilot/pull/24769): add new board corvon743v1 +- **[New Hardware]** [PX4-Autopilot#24018](https://github.com/PX4/PX4-Autopilot/pull/24018): boards: bluerobotics: navigator: Add initial support +- **[New Hardware]** [PX4-Autopilot#24147](https://github.com/PX4/PX4-Autopilot/pull/24147): boards: add new board micoair743-v2 +- **[New Hardware]** [PX4-Autopilot#23218](https://github.com/PX4/PX4-Autopilot/pull/23218): boards: add new board micoair h743 +- **[New Hardware]** [PX4-Autopilot#24512](https://github.com/PX4/PX4-Autopilot/pull/24512): boards: Add FMUv6s target +- **[New Hardware]** [PX4-Autopilot#23927](https://github.com/PX4/PX4-Autopilot/pull/23927): manifest: Add Skynode S baseboard +- **[New Hardware]** [PX4-Autopilot#23257](https://github.com/PX4/PX4-Autopilot/pull/23257): Add Tropic VMU board support (Baseboard for Teensy 4.1) +- **[New Hardware]** [PX4-Autopilot#23697](https://github.com/PX4/PX4-Autopilot/pull/23697): boards: add new board X-MAV AP-H743v2 +- **[New Hardware]** [PX4-Autopilot#23551](https://github.com/PX4/PX4-Autopilot/pull/23551): 3DR boards: Support for 3DR Control Zero H7 OEM Rev G +- **[New Hardware]** [PX4-Autopilot#23623](https://github.com/PX4/PX4-Autopilot/pull/23623): new board support ZeroOne x6 + +### Common + +- [Optical flow scaling factor - SENS_FLOW_SCALE](../sensor/optical_flow.md#scale-factor). ([PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936)). + +- [PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813): Reintroduce optional parameter versioning mechanism for airframe maintainers + +- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). + - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. + - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). + +- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. + The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). + +- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. + This makes log decryption much easier, as there is no need to download or identify a separate key file. + ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). + +- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. + Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. + This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. + ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). + +- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) + +- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. + This typically reduces false warnings due to magnetometer inconsistencies. + ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). + +### Control + +- [PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863): [Sponsored by ARK] Bidirectional DShot + +- [PX4-Autopilot#24196](https://github.com/PX4/PX4-Autopilot/pull/24196): Make control allocation and actuator effectiveness a non-module-specific library + +- [PX4-Autopilot#24221](https://github.com/PX4/PX4-Autopilot/pull/24221): Spacecraft Build and Bare Control Allocator + +- Configurable multicopter orbit-mode yaw via `MC_ORBIT_YAW_MOD` ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) + +- Collision prevention now works in manual (acceleration-based) flight mode (`MPC_POS_MODE`) ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507)) + +### Estimation + +- [PX4-Autopilot#23854](https://github.com/PX4/PX4-Autopilot/pull/23854): EKF2: ellipsoidal earth navigation + +- [PX4-Autopilot#23263](https://github.com/PX4/PX4-Autopilot/pull/23263): EKF2: Terrain state + +- [PX4-Autopilot#23185](https://github.com/PX4/PX4-Autopilot/pull/23185): ekf2: add mag type init + +- [PX4-Autopilot#23436](https://github.com/PX4/PX4-Autopilot/pull/23436): ekf2: Optical flow enabled by default + +- Position-loss failsafe delay removed; triggers 1 s after loss (see Common) + +### 传感器 + +- [PX4-Autopilot#23656](https://github.com/PX4/PX4-Autopilot/pull/23656): Implemented AUAV absolute/differential pressure sensor support + +- [PX4-Autopilot#23639](https://github.com/PX4/PX4-Autopilot/pull/23639): Implemented temperature sensor support for INA228 / INA238 + +- [PX4-Autopilot#22744](https://github.com/PX4/PX4-Autopilot/pull/22744): Add Ublox ZED-F9P-15B + +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Mag cal: automatically disable internal mags if external ones are available + +- [PX4-Autopilot#23064](https://github.com/PX4/PX4-Autopilot/pull/23064): BMP581: Add Bosch BMP581 barometer + +- [PX4-Autopilot#22914](https://github.com/PX4/PX4-Autopilot/pull/22914): Murata SCH16T IMU driver + +- [PX4-Autopilot#23023](https://github.com/PX4/PX4-Autopilot/pull/23023): ST IIS2MDC Magnetometer driver + +- [PX4-Autopilot#24121](https://github.com/PX4/PX4-Autopilot/pull/24121): Include distance sensor in dds topics + +- [PX4-Autopilot#23925](https://github.com/PX4/PX4-Autopilot/pull/23925): drivers: magnetometer: mmc5983ma: Add SPI support + +- [PX4-Autopilot#23909](https://github.com/PX4/PX4-Autopilot/pull/23909): drivers/magnetometer/ak09916: Add support to AK09915 + +- [PX4-Autopilot#23362](https://github.com/PX4/PX4-Autopilot/pull/23362): Add Bosch BMM350 magnetometer + +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Compass calibration now disables internal compass when external unit present, reducing false warnings + +### 仿真 + +- **SIH**: + - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. + ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). + - SIH now supports the standard VTOL airframe + ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). +- **Gazebo**: + - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. + The default installer scripts (used for CI) and documentation have been updated. + This is required because Garden end-of-life is Nov 2024. + ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) + - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). + - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). + - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). + - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). + - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). + - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). + - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) + - [PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471): Gazebo: Moving platform + +### uXRCE-DDS / ROS2 + +- **[Feature]** [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically +- [PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582): dds_topics: add vtol_vehicle_status +- [PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583): dds_topics: add home_position + +### MAVLink + +- TBD + +### Multi-Rotor + +- [PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173): [Multirotor] add yaw torque low pass filter + +- [PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943): Add gz model for quadtailsitter + +- [PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358): Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) + +- [PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507): Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). + +### 垂直起降 + +- TBD + +### Fixed-wing + +- [PX4-Autopilot#24167](https://github.com/PX4/PX4-Autopilot/pull/24167): Fixedwing: fix wheel controller + +- [PX4-Autopilot#23520](https://github.com/PX4/PX4-Autopilot/pull/23520): FixedWing: allow position control without valid global position + +- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) + +### 无人车 + +This release contains a major rework for the rover support in PX4: + +- Complete restructure of the [rover related documentation](../frames_rover/index.md). +- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). +- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): + - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). +- New module dedicated to [differential rovers](../frames_rover/differential.md): + - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). +- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): + - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). +- Added rover-specific firmware build (`50000–52000`) for Ackermann, differential and mecanum rovers +- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). + This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): + - Generic Differential Rover `50000`. + - Generic Ackermann Rover `51000`. + - Axial SCX10 2 Trail Honcho `51001`. + - Generic Mecanum Rover `52000`. +- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. +- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). +- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. + +### Infrastructure + +- [PX4-Autopilot#24011](https://github.com/PX4/PX4-Autopilot/pull/24011): standard_modes: add vehicle-type specific standard modes +- [PX4-Autopilot#24020](https://github.com/PX4/PX4-Autopilot/pull/24020): ci: build all upload to releases +- [PX4-Autopilot#24002](https://github.com/PX4/PX4-Autopilot/pull/24002): ci: px4-dev container +- [PX4-Autopilot#23937](https://github.com/PX4/PX4-Autopilot/pull/23937): ci: workflow for ubuntu 24 +- [PX4-Autopilot#23869](https://github.com/PX4/PX4-Autopilot/pull/23869): ci: add test for Ubuntu 22.04 +- [PX4-Autopilot#23574](https://github.com/PX4/PX4-Autopilot/pull/23574): ci: try runs-on Dronecode Infra +- [PX4-Autopilot#23550](https://github.com/PX4/PX4-Autopilot/pull/23550): ci: replace build workflows diff --git a/docs/zh/releases/index.md b/docs/zh/releases/index.md index 0902cce8f2..e8c4dcc49e 100644 --- a/docs/zh/releases/index.md +++ b/docs/zh/releases/index.md @@ -2,7 +2,8 @@ 这是一份 PX4 发行说明列表,其中包含每次发布所做更改的清单,详细说明了新增功能、漏洞修复、弃用内容以及更新情况。 -- [main](../releases/main.md) (v1.15以来的变化) +- [main](../releases/main.md) (changes since v1.16) +- [v1.16](../releases/1.16.md) - [v1.15](../releases/1.15.md) - [v1.14](../releases/1.14.md) - [v1.13](../releases/1.13.md) diff --git a/docs/zh/releases/main.md b/docs/zh/releases/main.md index 1218fccdf4..0e9985ae9c 100644 --- a/docs/zh/releases/main.md +++ b/docs/zh/releases/main.md @@ -9,15 +9,15 @@ const { site } = useData();
    -

    This page is on a release bramch, and hence probably out of date. See the latest version.

    +

    This page is on a release branch, and hence probably out of date. See the latest version.

    -This contains changes to PX4 `main` branch since the last major release ([PX v1.15](../releases/1.15.md)). +This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)). :::warning -The PX4 v1.15 release is in beta testing, pending release. -Update these notes with features that are going to be in `main` but not the PX4 v1.15 release. +PX4 v1.16 is in candidate-release testing, pending release. +Update these notes with features that are going to be in `main` but not the PX4 v1.16 release. ::: ## Read Before Upgrading @@ -40,22 +40,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Common -- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). - - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. - - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). -- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. - The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). -- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. - This makes log decryption much easier, as there is no need to download or identify a separate key file. - ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). -- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. - Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. - This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. - ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). -- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) -- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. - This typically reduces false warnings due to magnetometer inconsistencies. - ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). +- TBD ### Control @@ -71,26 +56,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 仿真 -- [SIH]: - - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. - ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). - - SIH now supports the standard VTOL airframe - ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). -- [Gazebo]: - - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. - The default installer scripts (used for CI) and documentation have been updated. - This is required because Garden end-of-life is Nov 2024. - ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) - - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). - - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). - - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). - - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). - - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). - - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). - - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). - - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) - - [Moving platform simulation](../sim_gazebo_gz/worlds#moving-platform) ([PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471)) +- TBD ### Ethernet @@ -98,7 +64,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 -- **[Feature]** [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113)) +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). ### MAVLink @@ -106,8 +72,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Multi-Rotor -- Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) -- Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507) +- TBD ### 垂直起降 @@ -115,29 +80,11 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Fixed-wing -- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) +- TBD ### 无人车 -This release contains a major rework for the rover support in PX4: - -- Complete restructure of the [rover related documentation](../frames_rover/index.md). -- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). -- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): - - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). -- New module dedicated to [differential rovers](../frames_rover/differential.md): - - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). -- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): - - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). -- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). - This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): - - Generic Differential Rover `50000`. - - Generic Ackermann Rover `51000`. - - Axial SCX10 2 Trail Honcho `51001`. - - Generic Mecanum Rover `52000`. -- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. -- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). -- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. +- TBD ### ROS 2 diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index cd1cf57694..a31d7d5880 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -345,7 +345,7 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: - [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -407,7 +407,7 @@ _goto_setpoint->update( #### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) - + :::info This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. @@ -549,7 +549,7 @@ If you want to control an actuator that does not control the vehicle's motion, b ### Controlling a VTOL - + To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: diff --git a/docs/zh/ros2/px4_ros2_msg_translation_node.md b/docs/zh/ros2/px4_ros2_msg_translation_node.md index da0622712e..2e999b28c1 100644 --- a/docs/zh/ros2/px4_ros2_msg_translation_node.md +++ b/docs/zh/ros2/px4_ros2_msg_translation_node.md @@ -1,6 +1,6 @@ # PX4 ROS 2 Message Translation Node - + The message translation node allows ROS 2 applications that were compiled against different versions of the PX4 messages to interwork with newer versions of PX4, and vice versa, without having to change either the application or the PX4 side. @@ -207,7 +207,7 @@ Message translations can be either _direct_ or _generic_. ### File Structure -Starting from PX4 v1.16 (main), the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: +Starting from PX4 v1.16, the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: ``` PX4-Autopilot diff --git a/docs/zh/ros2/user_guide.md b/docs/zh/ros2/user_guide.md index 8d2c6581a4..dde38aa9a3 100644 --- a/docs/zh/ros2/user_guide.md +++ b/docs/zh/ros2/user_guide.md @@ -34,7 +34,7 @@ The generator uses the uORB message definitions in the source tree: [PX4-Autopil ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases). -Starting from PX4 v1.16 (main) in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. +Starting from PX4 v1.16, in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. This requires the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to be running to ensure that messages can be converted and exchanged correctly. Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. @@ -378,7 +378,7 @@ accelerometer_integral_dt: 4739 #### (Optional) Starting the Translation Node - + This example is built with PX4 and ROS2 versions that use the same message definitions. If you were to use incompatible [message versions](../middleware/uorb.md#message-versioning) you would need to install and run the [Message Translation Node](./px4_ros2_msg_translation_node.md) as well, before running the example: diff --git a/docs/zh/sim_gazebo_gz/worlds.md b/docs/zh/sim_gazebo_gz/worlds.md index a66a255b76..18ab959587 100644 --- a/docs/zh/sim_gazebo_gz/worlds.md +++ b/docs/zh/sim_gazebo_gz/worlds.md @@ -75,7 +75,7 @@ World with walls that is designed for testing [collision prevention](../computer ## Moving Platform - + [Empty world](#default) with the addition of a flat moving platform, to simulate drone operations from moving vehicles like ships or trucks. The platform is controlled by a plugin which is included in the world. The platform is at a height of 2m, so place the vehicle on it with: diff --git a/docs/zh/telemetry/jfi_telemetry.md b/docs/zh/telemetry/jfi_telemetry.md index 5b02d24d23..e7fc2526c3 100644 --- a/docs/zh/telemetry/jfi_telemetry.md +++ b/docs/zh/telemetry/jfi_telemetry.md @@ -20,7 +20,7 @@ Operating in the 2.4GHz frequency band, it allows unrestricted global use withou - **Frequency Band:** 2.4GHz - **Speed:** Up to 11 Mbps (adjustable) -- **Range:** Up to 500 meters (varies upon environments) +- **Range:** Up to 1000 meters (varies upon environments) - **Payload Capacity:** Up to 1024 bytes ### Network Schemes From df2ee22d1b3ee4b6e4e15afec924f376c7eb8858 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Jun 2025 12:29:45 -0700 Subject: [PATCH 130/130] maintainers: adds Jake Dahl Signed-off-by: Ramon Roche --- MAINTAINERS.md | 33 +++++++++++++++++---------------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/MAINTAINERS.md b/MAINTAINERS.md index 426852e7b2..5359184ffd 100644 --- a/MAINTAINERS.md +++ b/MAINTAINERS.md @@ -7,33 +7,34 @@ See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/ma | Name | Sector | GitHub | Chat | email |-------------------------|--------|--------|------|---------------- -| Lorenz Meier | Founder | [LorenzMeier][LorenzMeier] | | -| Daniel Agar | Architecture | [dagar][dagar] | daniel_agar | -| Beat Küng | Architecture | [bkueng][bkueng] | beatkueng | -| Ramón Roche | CI / Testing | [mrpollo][mrpollo] | rroche | -| Mathieu Bresciani | State Estimation | [bresch][bresch] | mbresch | -| Paul Riseborough | State Estimation | [priseborough][priseborough] | | -| David Sidrane | RTOS / NuttX | [davids5][davids5] | david_s5 | -| Jayoung Lim | Simulation | [Jaeyoung-Lim][Jaeyoung-Lim] | jaeyounglim. | -| Beniamino Pozzan | ROS 2 | [beniaminopozzan][beniaminopozzan] | beniaminopozzan | -| Matthias Grob | Multirotor | [MaEtUgR][MaEtUgR] | maetugr | -| Silvan Fuhrer | Fixed-Wing / VTOL | [sfuhrer][sfuhrer] | sfuhrer | -| Christian Friedrich | Rover | [chfriedrich98][chfriedrich98] | christian982564 | -| Pedro Roque | Spacecraft | [Pedro-Roque][Pedro-Roque] | .pedroroque | +| Lorenz Meier | Founder | [@LorenzMeier](https://github.com/LorenzMeier) | | +| Daniel Agar | Architecture | [@dagar](https://github.com/dagar) | daniel_agar | +| Beat Küng | Architecture | [@bkueng](https://github.com/bkueng) | beatkueng | +| Ramón Roche | CI / Testing | [@mrpollo](https://github.com/mrpollo) | rroche | +| Mathieu Bresciani | State Estimation | [@bresch](https://github.com/bresch) | mbresch | +| Paul Riseborough | State Estimation | [@priseborough](https://github.com/priseborough) | | +| David Sidrane | RTOS / NuttX | [@davids5](https://github.com/davids5) | david_s5 | +| Jayoung Lim | Simulation | [@Jaeyoung-Lim](https://github.com/Jaeyoung-Lim) | jaeyounglim. | +| Beniamino Pozzan | ROS 2 | [@beniaminopozzan](https://github.com/beniaminopozzan) | beniaminopozzan | +| Matthias Grob | Multirotor | [@MaEtUgR](https://github.com/MaEtUgR) | maetugr | +| Silvan Fuhrer | Fixed-Wing / VTOL | [@sfuhrer](https://github.com/sfuhrer) | sfuhrer | +| Christian Friedrich | Rover | [@chfriedrich98](https://github.com/chfriedrich98) | christian982564 | +| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | +| Jacob Dahl | Simulation | [@dakejahl](https://github.com/dakejahl) | dakejahl | **Documentation Maintainers** | Name | GitHub | Chat | email |------|--------|------|---------------------- -| Hamish Willee | [hamishwillee][hamishwillee] | hamishwillee | +| Hamish Willee | [@hamishwillee](https://github.com/hamishwillee) | hamishwillee | **Release Managers** | Name | GitHub | Chat | email |------|--------|------|---------------------- -| Ramón Roche | [mrpollo][mrpollo] | rroche | -| Daniel Agar | [dagar][dagar] | daniel_agar | +| Ramón Roche | [@mrpollo](https://github.com/mrpollo) | rroche | +| Daniel Agar | [@dagar](https://github.com/dagar) | daniel_agar | **Retired Maintainers**

    6i+szwQydX?ManN5^3HI%SZP2!!>YXw8 z{9v|f9$IbG=QTd$+>>v}sDyX+xZ|aM;?Smy&N5v4+QuoPt1dU<)PPSh`H~XO35V&V4v>$T?fRJ7)YeB6|Q;suqv5 zk5a$Q)4dGi{lhRa*~iEeV}z}};4Xdi>FV4lPHOZMgJKGvdGOWQ$v8hL&-2BcRT@J+ z_o1vWzI8uhDzOSC*XsK+`&H1yDzq?;J*|pWc-;Ec zAAU5C`q9JwVQ|P}R~xIH`poY1RIOahPbPF<$(yTq>*$^EV5anV^i#4&k4=p zbJ)&d6wE2;CRxEhOtyp>bPrZypc-#${9uj*i#FgF&u@=c-o<0J z2k({4&+C-&I#A`Wr>@rKJUz8NcGy7IgErB@+N8EF-sq+`Z3a_iJor^Y8LW4-QGw2fPm z2ut_Q+w8T)H! zl%pLiu|eH=*O^%M&SDy#-kU0GtiyBiGhhGnp{;gQ-_2*-V%y%tSp$x>KeS;?6rGYa z4i8zbA1dJI0pHIbd|+mMCFT`zofORLz;CR6HV9xm&yY^Y~rjd26;--qvff+Lz)?Hmn4G2e6un(T=$9htr^LVb7`ssBrZ^_dwGL18r42DI?%Nli|H7kx5c=t#{>Uh- z(mF63SHVB2&X`YEOL$0^830Z|aVYH|>_JJ|UA3-Qikr+-Gbhv1Y3-fxT%e`Yh zdKly#zD1ghnZd$KjVxdeEg0x`ah+7ciGBxEbrvj#Og@eCNxTc01iqHR$7}FV*Ox5x z_7gI;!Bjl`>CD=U9&ar7<~Yd*xa+}iUyMm*B^I?MxVQ~ZI;kALRmbLi$@CQq6dR%k zr>q}a3)}E+y<6wH=Dle;;$FPgsrcpr1)a;0v7_eL%i+0i2C9kDobur~|XEI&FTZ&CAQuV-Cc zq{pI>G#?UcUd3|Qgz*?(+!E!01aI~r@zl8cnKvPajB3X*gSlFtTOA6SPsKLF*BjtV z#@;=*=QhO#BVr4m+QcOfD0y(tnoYbUlKr~%c;4&DBqQ6N?K47q@FY)jRtFC25*_Hu zjVw7~yD^%Wxma}C=XfW!-qZIhMJE!&+KXuP3`xVD`Xed0qH$z~7-NnR$HQ@eqk1>D zr4RGV$B7MutaI9>53rNxDxOz~uE_bNI`K#`4@?7tw)fx2mCrmQPsumg{RjWA)m-rO z*K;oaW0)x;S447j5#|_W89m6b5R+ajy<+)?+z2K;j!cv-nLX{P1A>orbUK|&GA&pXMv14Cd5^C!|UtttIYmF z7INH|%&Tu-`qCF4{e#d?{nSrSFElnWn;LKoQIBze*(qIkIbbVr8UdK4a*d;Lx}{Fv zm(tm%K4mGTz>rOEkl0SGnbwe0Nu!hH40<=A`(d&!9vuAO;vYTEgRXT^#00mi${{$3 zE50PI3a`OY{juFzjUn@4$1-csRpP2PUD~dqvwF_BY=Yw;I#yGCXiC51yiF%Q@a8gg zVrSd3dtz{WXEVa*xlvNP-rUZa-t;)2JZnfP^dk52Jec@Fyx$;=U2~+0Ew#B>^5OB@ zD*1m1kjY%^&$`aTNB^Ndm{1ix+Yj0$$ITRd#sH7|FW$m^@?MHv~Kf8U; zALGwwXFR!w_J(PRv)^9Koitv0X93Yi(3R=0MKX z@Kal1x(F;R-WS%A@nJdjtQw*rriC?1JP~_~(`5Y4J&mKs)2SCekyTu%`Z5<=6HoVZ zm{z}UYW_7baxde&Lcyu9I?mN+KW2?`xKoft&&CG9v-Gx*H_Nx-LtmQa_X8N1h8H;i zV7@#Edt78#o)4zx#mc4T2F#N2-T{O6L-c!WN^#Llr|5<}gwBjFe?%Vf+#c`V!>{## zGk(Pf@k_uO!QS|)WMAhCD;_xd;iBg`cB-cj*R&fCz-BJ^(w~+a^T86EV|TnT#S_)! z5pnc3_8IQJ3J-XWfu$n9aE?3#rYm{Y^O4E==cg?7bIu0r z$wq&Qkn@5EBP$wt_!H~e&)SY2>DYVz!BRaT#!_$UT*z{1q(7IXV)1Vs@rm)wp~2$T zr3UW|cs`Wzw9MdoVaG4#roU*(%$)g<&p1GhgnDv^G3$VT7*CzBB-cjnA?0Bdm0Y$y z)(Ub@W6dc_#<+y6oApg+*`l0ZWcYmK8Di?5DV;lYV3T}Eeqoco0j@FX@)eGGB!2HH z!@6ePt>FQuYu+QM$?T_jK2bp~c^(~$Hy8W4{86d@@Ujm%_xS%mIR~v1pH%SOUvS9( z)Y+dY1ICoIpl8S)7XqLVKQ+oz9l2jfciY1U*(a66^H^iXI7^5td8xWzikxSPrd)3* z*k|l^`@|K-eQ@D(L+B7ee@%LF3Qyh7>$B#pcD5vibMT0R_9C0IRQXgoi!ic z$ho+`W$LsGZM~30ZU=RK1nUI$tYsTO+O-9Bj3DpCN|G64K$=HrP=`j#(srfV_TAh1 z*P?nNaWFn5CGD2@dGNl<7u&Yq0TI=(h}U&4nMY)(IvqncG@G3b4n}O4ADiLz*g@^L z9h_0NfC)+Uy$ zAvfRgUu{P7&Nwi+@PdqcYPUVN`wXdPJI;+MLAv>p_p^SPF)HAldpkFc$i`3UW#3I3 zGLC~bmfG3iC8oK|C0U+d19=X@Dm#8 z!r5ZVJ#4TrHtXf_z*$!Z$pp5vmK^t~`CxJJTSX0tjEuYDF$T58mvzpE9Qe;YYazsm zKXI9J^jxFvCBsCgb*Iqhk_Q{*H8Jo{i4)i4q1u!0mTi8q*VdYXF@1E}oO57ssE!Tv zMju~h5&N8{;E?FxqmgqBeZlH@Ic^klk8J#HIVpU37=5r*Uzn)Q^$tZ}$LJ-NV^6-U zu_1ACam%E+rE}`?go8CDE`uLcp2%!eM}MtYo~w22_SR36Ym}K!7yQk?L*a|z< zpm>-+B3>tQhke2yVM!k4p0a+jIr(w8Zw!9Ooipex#ZWu)*jTxw4)#Se?sf5c)xS(Q zT)KeEdF3)|qq5slG8o-t?ASAvRm)0wnX_#a=vmKalmTj#xg-C`an6?Rx0J*Y9Q|-& z{LM4R99I}i!7tl39ru(@iORc+#)yyf<{qdq3sfQm9%F4>d`wSG-%MO08-J&;hHD-6 zhmy{x?JA^>`K>DcLSRVE^YyHm&zs!mdQav8ut4pY<&Su;i+ux)%3_x%2>4vx9`vRVG{r6fXe zLdJ&8-Zb5xa$p>z#^$jTD{scE@rtK*AhV84bZC0!bFhpY^$6O|V2E7$;G#v(Ka zgl?=Iuk3V;)%}i{#Cxg{SLAlvG(1$qn%Me~_P>)O*7*sN4=DLk+xXB2Msk*KSoS{} zp1&X^z8AjsV5%4a{g+4?;&NMwG*cA?G_XqXT^AKt?)vfciFmu#fCZezh_3ZW#}9K8ps=BAOFI zd*OEN>m2h<1R3hVp?2i*0jR&a;hX5_S{BSdZO!3l)?Q_p#W66{uYBXBSH_1Iea3Oc zlbQ#?=wNU4;WhOxQD<+hb5$DiI^6AVXw0jhcGo@k044^TN@Gmj;<;Ie<_6`S?sZ_D zT9+^s$WTTrgAM6j>*L8_O>3}*-!iU;9}avXPQ=XlcQzxcH2%E%rkoqa?M6vD)U9 zG5T(~Z~rEK_6uR;e2Ek?Zcizl7?+KiPTa;1zjwcD)bp1y%*GS?^?;WxvmsZbfh!gT2Z-572DEDyLq5eO5Y9RrvESg#Xo=azZ&T5^KLc08Gh*3i@3XJH41Y z_dv?{F)A@1ndCqpERf&hs%JgU@s<*EMq|6O1y1+%fHOJaZwC1f7|(z2QhXLod&Hzs zMYf^Z>iH3lj)Nuqm8&l6<9*1TbIv2x@iG3dgOfJ#Tx)fbmE{`6Hth4oI;OaftjgHr zJgeV57lKDzVzVve^g1!}LeJtcO+EAINIO`(p2nXwTzt~WI{3r5|1^Gn{Q;`a+2h&Y z))T|&Q+v!JMuE-Hv|dj5n>9WDQGeroSHNQ=TX@a1*#$mYM0Ci?)=nUxDJ^0`0#m^G=N!BMGL$=UbXd`KW~7FO}W zs;+$?pIk=|`j$@O5TVG4mMdAD*Bm2n#y3o1$KTou zzdsDgho0wNL;F>%wG#`(iZ4|97sLAR413R^*iY#~4q^=ZL?yP9FV;W2jA7fsGesAX zVI&cnSzXGt_#6{)jR3ZN=6T%{r}&dL1!|2b!smxKd`-;R8;N5L*pG>qeUKf~1}36o z#TZi0zaDgy#Etb{1KQt?c_%bVT#(yxSKL3r7?|+lGCV=T_Lx1U+Lrzg=g!F%J9+lIBS&=m0~03(%#SE zjWL9e0P%Y+p<>(fn<;oiVBrM_m7L-6fBVfG=S}B^f2hsm8fE&vsNYU8m}Vfew=X{b z3jU4Id*1uLF`7dM$^t7nCP8dMk^$z1Om0;S6~yM@ee%q>s0rj68)FA5-x)ln(qzLV zarqx_^E;1x-*ybOy`z1rwRSKTmWRN|vQM;&JTcu&y zG*eNH9e2e??4v8RwRI?VQU`y)x$5TAE1v7%nMo*T#&AqGNy4X6)c*zc5zZ9HPWo zIQs2x)@vU?)~{N~wrMa=^Q6YGwWZwm^ytz{_QB*FAf}4v`tWCG{N6HCPJbZmIDZ{S z4B4XnN(`>@x~z5|Nc^?KgSj8{zP@Rq; z7JbOcPas*#bC2iOOCEpxiQ9L5*LU5%`@6r}HRr$MtJprS`#^pNK7XQj%O+>hOP{s@ z;;J15YVaU)Uo_>I#;Ndj-6>#YtOTBQR-m7l*;wY?F45egKCiv6`L(0j-~N>(irT0n z?{juwH)|a#z-#<55g3ERMC@CqY|=W;eD}B&l!lk{s(U1Qw@zQ_XxK4SVV!&C`Qb{a!f3(!43Z74b;a}whaxZrh}JaQR5=F(-%B=(xi zo=P3t$lw_o``-)bYyjin^?lgq#Mx)P)hCB)#rDz;-yVy8k!)^Cn``iIKP+k;Q<|$& ztgkA4VI;CG9b1edWJ{h^EXu!Psdy}!amUTM-`v`M<(cb@iHaG570xY`zR&AfUuwu0 zxCc%guAM@bY1>UP zbR#xs2xTs;P{t#Ze#W+}`n1)k9^57Y^YD|Kf)7~-C%==2U;d+yF zeAqOON%(0eZo!GNbvSf@>tM8DjXAmfAeh=Zc})!H8}CZM_>)a5oA%2?A{yvN{loy7 zm9S%51lIG05JJ#z6kPa2tVQ)^u2>rr0umHl;GqgHFVm{_rYhDHa^reaY22;d?>Ox^ zVN=C@)nEPUJ8qx(%-_5{_0%uk-uTAnr9U=$n2Ga9ItL|7aLT>AAz0v_yCV8T|zN2Tw44p=b z0Gcd|zOF@ZrEHouW@r42h1(_TVuW0eU2fFurDF8j&K#0{AaHRna;N{`scza}pg_ap zwV(|f3Qop%j1nJPm;U;;bL+&<(pd-g27`4W zEgg-~SrUevcYJ8dPge3FD%hjn2*m6^-CciYPdATB#ebH@G)*o;hg=q5_tANl?Z5i? zFCJ+e-tcd~A_FC^V8V28a2EKU)fgRfXhw(6YD$z(47d;Mz7ZgN)E<>iUDES-$UGFu zqldE!oQyZ#tXuAnxvw&2-zM(dd+p=kv#iQGD+mAe9!W`#QWHP;kY&C7Uy1P3D}OMb z{|{+=u#DC^|Cug2&>0>508rn+;CM@xT+SC_Ge%B{N08)4zeEbA_-Hl8+_l5L_aU`( zkeB)L;4V*XGkoZ(vgjfXtXtxN-yVS1T!Vc&mOrTKkc_Ox@M+d4TF8gYCFWVHoC}GS zU$b}d+3Pbh!6H329gS;DwDuUar!rTp&L!4~dFvIc>ixVC+g9P(y)Rl~Z*-&AwJKiq zR|Dp6+dNsj#=7|uD^|1Q*cZ#5CsSDgj0ZW6V8$Qo_NeEKZ))4GHLC${@ZIyRxiP$L z?D+Le_ZkhXo)KzUNByQ))#97+6)!}F&y*Upwk;dE-{Ifc$9Bd|=uqX@Ip@btW^bSS z{44m0&`*5$&l-t?n}!WxBsZ{pOLuNG3Whh>{AHdddp;l}c(m;)Ist20g0G>`V^FP! z94rrj30MjSls_rvWLxV{48n?)mekq=o&pekg$V{57$`>l6(_*T1M~ObeMye zO|X0x`8xO*x{ME1=fXIB%fT=g`-tvomyBHa*Efjj=U_`-IS*LB@x}aO!)5xqcs^KF z*jyN2rWp5ikBtlzeObrcz>@n*P6hVHtslm@X}<8nJ8!@78~?-YPyMO?`1bnm$zP4j zn;U!eXkbj+e;TwYYt8uv{fHs=5@S-9aZ_ba9ir_8G&b>1Jve%HQ6S6to&KuK6JC=QkM`P|Dbx5C zKjU-RL%V~@VxVOGcd<>1d55QCqsG>3tLGE(p0Qy9qkHC?GHcyEk-fI@B8k1;ODHC* zl&r4CG|mTK>nY8BCa{U5YV25tb!{rPl`F?MUWC%lO}h6vY8&5N6MID6p7G6L_C?0X ztkq;9viIkyr_AG`cGv1E7a5a=y@wqSc%!!^=h%Fx{zLvCL5z6+%QydYN;T&K=RgVT z`S6g3@s#{KJnO|iI*N_L9Qh#%-po<5&eVx3{BRg25ggxBO-HoOC(A|8(l=)l>^-M* z=BZu(Cr-wp+L~vsR*cm8#ABSZKS~EbHPq?wZC<*y;d?t%Ztqz1d|;gYM6-HQj}3&? zXTALsRn~*&HHv)n{*u4N)c6EH#lxb^Lz&M#xBKtJ^ZE_9&vE$K0f9!=Kw{$IE zGG2_1K3mDv6SedoFTp|*~UQA&F*Wk$mT zo7ADx&;1jNPe1e7NB)Mq15M4GimMa1a?a@IC_Y740FA~OyQ&o1Eac|yEb%%(J7;H|taqdRMxSiwJW zHD~_v41f3{fBZs4d2_#axS)$mC4-Hru{(XJ@hD*rx_}V(K%~!Vpu#X9p7cgU@Fyn&b2163nrf-6BqXfD@5&a z$15L%^j`W=a-Nr)Xus?j5T7TWct-T_bqOx&FbQ`T(^qwI57byL){A z@7g5SV!wRbm;9y+_8YrpTg5SO%wvo3+IKzXXkTSB9-1}N1wFhr){ccNCi#VDFu@9T zeuXx<+W#^G$=EKxwP@IS*_XD1T4A5uT^P+L9wSKZ))#o`!^phYqU+>AiQYM%gjr*u zKF`hCbbVAZi@w+#c)?VfF=Ncdwi>JW78we@8`EIOJ&Lidx9#i~Vi299KDG5GPhumb zINL{$hb=PeIXT6!^)4r@maFTY&CW}BED#X?_#gjokN)Sg`43fXaxDng)IE$`=74ab zcuZVlI5!3@*!+lhEtn9y809#Yw+|Eea0)fn#Y9+5jByi8odt}~!=!2-N+E2N9|Eg7 z9_Jk$Ds+c03rgD}Sq$rp-s;-Kq0HF$HzkxhUB+qO&tsf->@UMZwV%Zv{TdG!*Nrvp z7Oe|){TT@=x6MOEefUj`WZ_)1CeeCO83IS=PQPj|`pBJb=ArRn%futGAGO(5o4Pt9 z4Fy}UriR_KgT(_Ujm_j-WW2sJZWfi=YMy6LL~S;9;)6V!94U*7X~kXLuYBe0x2K=} z8@CUB@Rx3HdgHGt&e=2Q_QM4A^zq9NRdaJ>?S071VH7OcgIOoAND2(_4}R~tY5QiM zrU@JPwh2E|TbBwqW5|BA%pUg(0lnePSO_zYr#}>7Nh8*o+4@vFR>Jkrn^@#bQNuj0 zYQ>$=;T9%rV9Dp-m=G%-0_NWUPRW@Sd#xdS<{^iNTz;a>AMog30L=eGL!P|aYi2pw z$%EE@IN=4B<^-}l0Mdtw)7V{zRmQBddZq+>{;|71?5dyG3kGtK9&V+7#Xs23v)f9CEHjvDCl9a5amE%69s_qZ zxjKCac4D(eG>0$oZ~N&OvCr7Yddafw5p#@Kw{tlqU#jFwl>S5{=LSaV7kMN(&5r%BytXoW*0ayx&AB*pYD4Y2r%QD=9vG*B=wqLFCBGCq`2krc zdK8oTfzA&b3H!yk^t&bxRb$V&AWZpSvhQOkhPU~Oj_3qKF-?3k zVIKJRPi{B^#XCIa@44c9*9XFwGBHozy7h{GSrfj*cw8SW{bl0(o7gixrTDY^j*|*F z^P6Y+FuyQx|I?gdm^X4;r)NA~U7vgQGmrigp|`#5$E@_?l$_vGvk!;+mqo%kIw>?{yPKf zKY+L?e&d;#`OKvhm*~FUggq+NX!Cm;u-?&go~_kmStQaho%3fMzmgBRN$G|){oYJX zs+W#CxEUV|vyK;D@Ux!gE&nkOnI~ATXUxHW=w=_prrDOSj*I4+tN8)}$q-zy)>ij~ z_l3r+hFTSC#)r#31Y`{x>p-_2`No*ZIua}D2iuVktH$K(I;$M_{ej$kdiP<<`-HK$ znyPKp$@}mYCll4zGty<&mbNa@u`UcTw__h~7pulvCl)38$TC)0+R=^9>^=4p?Z(~@ zN?Hq_o!ak-hl<+p<4-=+%wJQ~edhenV}lVB$Z9>v0r=;GiQ}&MK36cWUS#HqZ{waw zbDrLN#5GI@7xVTNy_0Jt$AQKSiF3_crfcPO-4A#+F*epce&W`-bL}!t32(86HF~NK zoNI3g#M(y_FW7pfbx)X7`yMiD#ltOQ%o+!^WHx`QGd8TnIsd*c0rEJQ`G92n0}$ zA!Aa)L|||^uerDU%d|Vq1V4IbL>CZkt6r{cLv{nk^k?fdx3*{>$KfjS9Gv908l%Qi{e2} z=Ni2y0pELL{BR#zBhh@d zDfH9Awr54Ffoye1L-!7Q(0d8R8dvdp%>Jb0*OKN&2%mIv7WqtJZK&m6OxNIGbT@i? z4nm6!Dw`V0E1WU#v zd*rn!XKCWa3)|+SAmg0a>wlhSPser<2;+Gp&0 zY}&3jR_yd_T17T{AMp9#FIpOJ`@T!pT9t8mZ5V6G@bJbj`XF|Ejqi+;8hRJA|2qPH zQ-B`~%x?|wMMr+^Ge7Y-T0MRzDi0jHRmyDk0AHH-g__OzU_RyNKMzdb53wph0B-6N2MyYl6p5qt(s*k<+ z$`1u}FV(%LXu*~r9OMh7;`E$e=%}9L4r{QV6JF6zgnsVleojiF7>Yqarl#-BsaFy$ z!7zXUa(){lHq%;oIhEi zcWRmNd(+^^14S2(@m#={R^@6VbHt__IlrQlxWHc@&96dTUm+ehAa96C7z>J4a)R47 zGmcSjxQPXnI45rLGq!AJ$pz0Q+M1j(Y?BYzsl3O9jf6|$<@b!-uV2NXKM!8vqcle-JvQOvA^ZLx_~IKi z>rWd#3Vq~GoY}zH#1zItFW-Le_uhW{&Ii}@84|D95&vC&$*bZHcF~_UzbKJ6n{c_e=X8RKHe6diwX3K;7h{Rc$f+<~GL|&ZZicA!#q{9(ZksTL-83_N=siY7 zF!LU)LnrU@gvlj04(hh{w0l@CO&2ewB% z?io5uo;GXfpB%7{=eHn|OUyMtTB3^=Sg_5R*R!WMb`DNHi|@S0mNFOG?bhPeyLpS` z=8mpike?~jsds8#>i8^_zy67d&J1H6e?!8GPS#1U`s=;SG&)8p^IcQcFXv~^Q}wm3 z;Q>8vfR(!)`m$GjuL6q-_lVxRkmxf-ZM0a2AnZMvc%OdMmfq&&;+NWv!`N>L6N2%p zUozO{asD|sdD*4-6++&^>0!@yQa@12U-DQes<|e1_xHH7m=%c#X$;ZGdL)%7{9BJl z!aHr=50F3+*W^v_F>?=JYp1xwC?86(8--l$F>9n)M+f&Q_(uk8D#YC%ex{7DiMT=a zeXoZHJr@|Vb;fh}-Je0rOMmBLNI55cv^_+vzVCZH`+#Zgn;To#m>8g!Qk}t4TP>dR zJDA{c4vHAd`S*t&qhvlj*dc!TjiTJ^Ef;gy3*r&u)}`0Ht+)DX*S6KxTX;04_4GJ; z(3y#ll&o{wHb*fu@>W!WPZc^c$Dl4V9^tV~p20WrmwC5E%#CepaC?gTx7#N^@qgal z@+Thg-w1u=BOje!Xm2)mz_5TB&_?9(l=Mq`e8z&$92Wo@=>k)(`nJqPpC_ZR0f5fy zOs_^0*&o;@5zpceEJ_YPG#-aJpLmglWIgsx+YWdbFAm79i~iIQym>I^5Fx2`sNnnf zZyE7t(`>owQKQxmJW$#UWqi*evGiKs#u7Gs@bwhyl=P6EuAO1U6oyJQUJ(*{H z(az>%nl)G~Lwul}gF-mhVdw*BubT;-sV;VWgPwkTjjqIQ;%VK|=X?lHWb+~EEY3?G z+VNADg?V8azc;<=_Vus7>-L2&e*E_CcmMqD4d3^?#*#xNuLT8J-ltzJ@G(~2DJvGj z4lVvEUXzJ6gpBjwzDq7zQG3x_iXQSZd(uB8RNv#H_q11Xo3W$a59#0qch+LsanA37 z8d=#O&#=Arh-${b6@B;;+`V}=Km0=Zw4)b1tuy8xT`os^`;@V$+VS&4J@zz_oSMS9 z!TB*Cq-}edvSrr{TG!}gA`g}-W@?qIy}%a=a?@93B3^vC;BPMH%Z77bZhu0(Y5RtA z@-cbvwq-M8f5&*nX!)J_jD^ry8>>F-nO|gmv@vL1t7!^9V|$d?xv3h9#p(w(*aeK`yJ}A7?5qaKNplz`GBR-^No;=w1Af4;pU-*HJt`9OX(pW{0#wgt_uzNQc=dvbJZTPB zN6#So_}?|mml)&xP%)@Adew|+lV=wXqq3`h;-Q}EP%ze3a$<0|Jz9;{!r4!~&-gba z=F3`Yo>}bY>{)+#!+Aev4&auJDcHpfw&?#+6!Tf*66`%Qko0}eXW-U_Oo_4R!Jp)a zWmU2_a_%B(KQ!MnlXeQ{P;4XPFVbe6qBo_o@DmSEH_t!&*-tsn5Oj5!wGYmKQhSn!zJU@ zW&DG;578ahMf~~E`?`@#q9cw5`^rW-Hpo6;;E65Uoxba_k0Q5a&Nys8`i+-{dG}g% z{rb>-en`#3)L5}@yJ0^fuUxXeVCRF-^Uwd?+q>WO^S3v?>3PX#J?)3>jIo0}t_$*g zplkecIPnu%t>N(y*M~M_CFvODKy=T#LfniKla-f}OC8)$;*Ml!&xF4tm8p7q#v^2hw)%R@nUdecjsQd^hi5k}WNF@I0e%Eg4L+`Lq} zj_fbTPZfOl=!&u3ZVBTMEUsv5p7g^4R-2zX!)lpN75mh3ocUT0_N()VwYmNZQ2gc` z$k>N}^2@x2%brbavE>*tirpc28#i=%%vbm* z@?VXdqr{^6%&~aV9la=+X4>jt$BKhB_x*|6*ln!xMOfob9t3|&^%(oex;)| z<+7*H#T)~=ls|R*CGacmvnDOJtrGp>a%{#2$EZOVeZFizQJXv`H}abt{Vk5_!m#yE zuG#M3T=r2K)k7JJ+~&8*S;O^gFmvpgd^v$%+sB+)J+ntvHOk_L#-jL$XY9Anyw}oe ziaayOgtsa=rxh=&%KiWN9eupeV?6g(Dw$9^DOlA z21o-uSmB`}DQ0|Af%DnOwMjv!ImkhPGS&+mgZ`J5wB8TZDD)S7hAZq=y zI1N--hA)-l(aqY$qK&+RPZ?e;Grk^9=4R0w7cY2<>56U3=7U>qRH)}-Gh)jDA(`0# z*?f#qM~~kg$ChgBM40!;v|u0fBHO{Q!Atw_w~0Ee8RI2h$i%r5qss2U+9dT9=tr%@DRTIvE9UBQ`&($ZPn51t|{`Y zZS+THe{DyMdVh_d2z}w>xA(s17jAEQ)2~?uf`@l8AeWkpwY$$6_X9=!>Rf0V8t@Bo zFwNTC^QNtf^cVv)6~ve^(HX(YP*-P(R`nz{hceUVEoE)QSJu%RT|=H8z9HK;Gd<>} zX6?!0)|v>;O|{t^;i32Z)yI>^`%14BbNVv}2)|VOob(wfTi~_+$OL2fOsaw%xvo!g zuzJ`(`8B0{_-a9g^V_&{!?6u8+3Z<$Ca{(l7IGYXl>JlS z`VxPN)dU8&u|-TKHnKzg(svT~#>;ptBb(CG4{^0$imvdx@M@ca9o6cnCT{(Z6S-B- z2QzG92Y*_&A2Dnj#c$iJul%Jb9$w4gMb7KUPvn?WVP<1>Cm813Vh%simzd`R6mng& z^cnG>b)d`lH~TcP^myW9{t?L;%NkK8XGLJ@mkj&=M48x#;A1U%ZuTdQ_!z9?8wGw# zg)$EYkR<0W`*dQeVb4LWLxT|?S2^dzc=mlHyHTSff!-@Ar$JhfqcDx?u z89s{U;0sSEYnxo=8R1*sdhzz+i{J7Wy*#j6OfukU9w%OWkx@mncC=>9CJDSd_@JIK zHIGz-jT{|W*KQv=j+oz*c~!bUS;IVM5|8GaIa3dRn$w;F)egn+8+^7c79`>I-Whv* z+3T}R_CgzHb+6~b4BD~HmDbwdhy8vgSa~))Sy#1{2Yeu>?=xufVxQm1mz)Dxdp|oa z?9`m!eGUuWU;m9S-QN1vw|eYh^zc8H@UuT>VflDZ3i5Ay;-o*l&q6wo6QJ7CdnFJH>L6>%zRclg zTc;fYM^Go>R^NI!WEq#@Aw*M4xAgVq(S@{r*J6^OF_h6Q4+2Z#eS@Qz*Py7wX1z>_o5jdL+bYFays;D6tv}eX(>+368}Vz$ExDVv zXR1(SX!!7u0wKqFg-q~7mU-JBEFPQj;E;|PjK~#_{k5;nMp?!_tD;rJq9I5aG41Jdp747TuiZ2iD7)7mSCfwxyn+| zU8*j~{#h;_J)D>WE7itrE!BnHX&6J#KH}*8oqHkJ=$lERV9R}$Z(G3%&S-*ApWI43 z0zp^CR3#p)RpN?Xq`j7mExY1#fBd!fA(Wm2Rv#ZB^G{(c`+djN>&8#mG=`q|98C5R znenYZ+4Tdtm*yNy!z(A*4Ry-3#9RBv6kn4^gROOL*}%elwvrP*(L~99J?-z zyPtUzdR#@HhkVKSNzoNqSBtqCC64bz%E*TB52ky>4! zDaDGczpTKJhPuC)@3Ug||H$|qStx3b5e@9whtrt0uQcr=?U`_FRebJqPP>+$(?`g@ z4u50lF9hZc@VUqHwA$#Z-{+Uu{bLnAGa>QGn(Z5dha&swr$6`TKN0%LpZF;$j5AEe zF%F2mXnh!HsZ&&G}08N6?_JPi97o-83hb#wH^^}t=p?4A|(h$w4 z$arO2iqD6k#UiU&>x9Sn%#WJ#!>WtNGH$sAD~*n)Pdj!!QfB1S^4OM1obHQ%B&p=_ zuSGHDn@M75oFJEuvv@NoHvJ&wO*1#Zy^b;{NP}+PiG$zhnf0cew0wC8joR>x&c$xL zL$qgt>$1>>28~@9$iaRCR!lua%ttl)DBfr~G!mz=D5i(`LXPDRU9d6PkjG&)ylE4+ zjfZ~mmzVJuzV_tp>8F4B_S94V)$NUMcwRiww}~~+`s{;{QRy0eP+D96S=TOPf5{7# z6MMa)w>j=#)qC5+)u=6Bw}fvV`8!rq?zT@M_h9FCLs zb6{2mLSNW*k>Y4)V%iJCJUmR!_u+G4ni9DyRsXgdjBe8%0n3X#?D^m}@2tm?lVB>< z6|$nec9hzPOzJc4X#*NR_d#F&=mGDkGg!NBJQTC0-cx+xq|%rvy4C|(c66Zx8!cd$ z3geh?*qzmDJMTr-UK329FTK&LVd+eRH;6RO6n)Qub=$Sn$c8O5=(FE+sHa{1?oS)C zedCEPG`X*`?p2)<5g%^g>o0!JjeW&T#Q96^`O6n#O+IozJ@ABLCpO03tYIH4Vm<&W zSvZz8A99hme%4fZ;=I8&{}yucKy22Z2ejB@%yBpgoxG@9z@<8Qw)=Vq(er8LMbJl;hho7yVY@I7#K14cvtUCM6S{!O6|6<9s^?@R`)w?iLhB`)U*8EV%&OKng(r-S$Gv+U`6t|vb`BFZ=TFkwnfE<6$GIX*Y*ih-b z)sC%=X^)lg(Y=SxN168{u^?C)quTw0kablZqi4n;WY|0QP4V_~o%bNRay}#Ly;9uW zBO~us8T;A8!DTtgpZ7qIsm@QW=l-Y?Wh(Y3U&8U1TlrFkpRVy!Hsa1drQj!R{vb29 zvbXb0QJm;y{Cdwtf5;fsZzTMIaAe>em)2R9J~Bw4OGR;jJT7w2mzQtP|JoNG{e#fk ze)JvwUFbYu0z$?e5Sm>e6%D-RH3V{Qo^{fjUnFpV@?kv5nrxY+IqxiSB7r&Sb4EC}VE9E>^}(s*rW*0~o`W+X)(#xk2NfCW6h2nfVnP z`ax}e*Wy1h-WRx$V66Z)vkfCvwq8I~y(S>S;O2yu`+FNgFC(*Dz~7>pZ3U z+76|*UB6R9usFYwpIrA(2UWiQjd$OE>!1CD+YkT9e|Y=u@A^zW#GW@4O4L{hw1r9P+d%V~)k_Vb7t@Ik?W&3wQj9t(%_ zZSYNex^MNiT<=HG6MvAS5A}WmPTIyX{2}UKx}MXaa3$ybHvW`FVvdXYDlxn{ytVK1=gl!MR}D#xe0G zza-cEYCeU}29`}@BHxPuI7cJ6Q}@BXXLIbUc*2H5&px?lpC87; ziXv2wU(}w7e$z2_PxS|a{cxQ^uTJ-`cL+FZTo%{gyBJbe4)CqMD%AA~;m z!JiC}QG&7pXglR-^Ex({$pCl5Z3hy;3`2I}n5XW-o&Az6$c~-u!Q!&9@a}?mV~@UU z$hqO)9X8foy(&5EJQy4*z9Cz7>ZOZKL;pdYA@qVTI+=-lF%Bk6B;(4-iU5t_sg9g2rqtJV53l@;pd=;GQHs_T9}Lhx0JfTk~9IK9V*|@080t zHS=lnwwtnj`kpB!H|6FV8DiQS_$jBB{aoKjb=^hLCJn_h`e;WSAZGGd{LFkx=Dzl| zcio=<;>U0AeAi#~pU+0;!VL{$4!o;RB{zq!x~bDoyAM&|fY4K)`k{c5hhgT;W|E{8 zMNjg(H!UAYuf8!az32&+q!{2x`Q+E z&v@fx8!$7j3VS7F`jBM&>hJxBfJ$X}TUTy|9dEqB?|pA<TAG5*HT|(+?5z2W zL&lr8<|E^LQSn0u<@oo1jeGDVFZ>{GJbXcxv6P%m?boN|Vr;Y|7HVs5?Ki!hUldV% z++?01{A+%=5a($_@b-f^f7Oh&=1UFM9*X?Ps&t+2OKsMd-Nwhk%{r)xP4t(y^C8y4 z_bSBwH$tp+Fvl_-;$M( ztNvh5JTcI7*fHRRQQ9t;9^;}Fr_1;tp662jKSwKN5%I9mGx5s z{HSs;kKIH+VdG`eRZw{KEZn- z^%<&;3?;{^GdW=<+u!%E&QH-^$-dxM;H)ZfXkkCrBm1V;-F%;&d`@v6ARi|7VzC_U zo=I2v>-b6a?>ukCCB9&^PL*XZ6P|}t8fcjCjTqF|evp9!oxvIm#lajHx?WvtE2DB# zSLQro^P^)1G~*X`#b>+dk-&NmvHtAG`eOW}*Q%^AR%jCI=RW`Jqkj;3=acU-z`OWl z%#BobOyn+e>cYbUW02qZ??J(M0@MT}5s{}P7zs*b_aPsmnVTH?dkCv-LFU9iGS?&; z1)@t*s|0=m3zgM4XWR+Fp`zk{JUZVBFy@>-|$J;CEra09uk8ePj(Zd+nBLeCr-i!uh|@C@df?7V+R^*#-4*sc4ysO-_q74 zwp6fgDa%Ap$+$F*O zC;D87f7-!{uX;JZQi3BGk~`twYapGx#kUSRmGz)29l!tozVG&1zx5ApZ+qK+di&#l z{PSoF9!g;bpmmZW=nrX}G4VBT;VD^aWKC*jY=(_XDCxM4JaK9q{SY)ZOscaEi2;7} zAC$Vtx9++6j1bpN(#I9O;CAmpa{SydFgGoua^8^07cfITACjvPTWcvE?^l(?>;6CD z#RueahD6UUrCXTso=q~#)?^@8BIP@^2aQ|5!N=D*T^0JX~~*(XsNwH>GhzRID2(4^h1J8hi`?!%CD) zor}ag=W&mPVmEPe!C&6frtUhoeP5QWUiRZY~v_F{N^=#!8pN0jbis{lm?q9ItGK@^~D@zW9U`q zdCW-_8;$Qt>4#Sx$IJJ}-s|S9JjIHko0F`&KHY%p_7={j%<`q z*HvF>kGlpA-2oI^D(G+VOlXZwfuzYI(Ya+C>+Gx1qWQ2kmXWECHI{qDKF?x8FV;YD z@?Iofr|j@V7CF_(qem~xie-O6J3J#=~UW@h>;DQwHC}6r2+vF6JX2_+ts5dHQ3w4}IvDZ*TsAFL^HVWtS|i!Dsz`2aC;(J^SJu z>_b-cY+`QLE9OJ+cTFlw72fFeVZ36Nf?e~D0I$-?<2H_9Qhb;3hm>K=zOe|nSVP8C ztIZty3qpo-=)6gv`e8%fUo6a;B40Xfgg0~WwREgH^-gU&X~+HWfjl~QF&~r2x#p6p zYe<~C7j2Uwj_Au+;{vTQmy8vo4O)A-M_qO41)o2#%?&U(8oTft2Rf*%Gg@ief_Z7{ zCD}}+4A!G#b(A4ORTrQnmpMLg0Hwj@n^(=nqvV}6efk7~GQNqE5vZ}_u5v9nC6vF>ePP~8s({Z$_*_WRI} z-kdl6^4A4>GZ&uNb~W|Y$BjGnH0)7u8kciz@8JJ^u=Huds;o1y-f>7BL$Osln#@`jvQGSi!O9t=d7L?v;)2I*bg1b|D#jcK z6o~AbafT?p9O9+HhoI-FYUw>BCq@mrF`N! zil2Ht@x&9i*S+p_wh0Q0{EEXt zgJb-nVt(*Yd!NA1J~r;=UG`#PlGs7lzG_{Ge|X6UVk<1O7L9Y{27+7B^)Q~`yTf_p zcr?7~_Q_9v^3gvCJ@wQF)j|;!(Dg#O$2NPg0MOkX(8{VV*$IJ20?t8i*&MoY?CJz1 za`S;l96NzkYs|VS9!ps~odkyJHj}9NcC?9_KRS?24Ow3L{a3`4a7ny*sM4G+<~x(u zV`|c4$m1GA#@}Z7=9?I-qWP6zB$qJc(A^uzgwmKy5^CHDzkUibzqdL*v^Z&aP5eS? z53W2UDhP9E|;m*>^l< zmGF+xMaC1^cZ<~bVXfH0v)78LC}J!(Eb-d_3qbV0ujI*!uj}-!Tkq%^n|Mkb?n=SJ z2Qiexlek59N@ec)24m4p;9N9q^HS5??UMaW%i`d$yUqn32=<;e7wo$5@*H_dj3~;@ z{UIc=uCI>kV9K7&81uO)<_1WCw%_g! z>Wp#v#tIMCrZ(0Gco|D^jvr;&BL-MaHhi#Yf1>3!kQKM_|?9y>!iLcR@ zcK1uyM-pp3Hpl0Y53PpDHiW0=fcY(}GJO+v9FLS`XPb+R<>_xZle&@X(BK|@6mTRy zqh|_p-gjP8m6a>Wo1ABq@JCN`4&O!(W<|xJA+DNF2fHVK92s6;MGQ0Vwyt3J1Vo=V zm*5We?W^nQd;f_SdjT_k%D1()-mCbTJfyaIbh|-2eQ2u8PuonQ6%*xLpE>*t;xYC@ zeD}TP;92&jL?3tqyYX0igFX|YQ;u@_qml7zm)zSbPq~-hGRcADLH1g(gjx>`Y^oBd zjh!-W2s>`+vb4<{Rbs|u#){W|GcIENY%JZO@TDYH)YvN{&GZpJgsng8!Fowj^TdQW ziX>AxsCF13-;z`CWS(~J1sTgZNQoS|zz4(Ez3y>;X!PGX@LBb$+duk8|Lg6Ce&~mc z<6-pB4?^#M|NHGu7I+uafarst4|6SWZfHEDBq{R&Vs6^}ZuHU-XObAbfn)<_F3DzP zjA*>y`mTq4Y-=3eQWt0~uxz!aG-%=LhDUD8(r%!4;_ifpBB#;?(U|pPZ)~F22e4!o zKN$5Yo|It0a5o~H3_-{sOQSy1c9lyU5S@DC52K@Kk@yeVcF+}_evNMTk3tMQCyI?I zNKIi5A2ZkS+~{)%oDYGHsZHmG=nnw%d%yfC>-r+2RzIdSM%gytgHD{0!M-QF9S)2uMc^JH9RXbDqHtd^G0)WnwxMyKcFkn7XmsqO4aQ z^t}%UOY~=byLX~rAMj_4I)uKi=~#?elgF`XzP70(V}I2@>UBe8j9i&H)+E>|(cAGp zq*=eH4~_PV{8Zf=x+Ehf-G$j3A~En^6r2Z0Xx|XA;UQ5lbijBu-#)hY2b1|z$_2(pvCePa`bc%g3u4`pC)j*3|1O6IX=0Fsh}lRzFdk}~m8f+phrDmVq`|I7 z*MuCa|LfmEpnqcFdye(;M)T109ixd=)++0^bKVisJ32IMz7+U0%+$((_~rOan{jOL zo{Q_Qjj4D%zJ}J7vFJ#@RGE9K&zm0PiM|JCEbH+HWuW*QzrqV=b@?Ej98io17&0o> zCf??;W2kW0AmXAb^=Ph2gg!oKjZ$HEho^w;^d;vXHM>>J+?=8W^G*E#zQjmYt3 z?wOZpvFzvs<6i&Vzlt+ptT?jBP2F;m<)?kpne(*+)_gd~`Qx*~eECbEoQ=kX?IC2> zp4K=%cwcD0(2h^3)iCZAkAr`m9p=Xmw8u{T+cAK*zorI1XNLE-h$<^ad&i^xxn|G7 zS1jspOqPr+Slo^e*2Or&qtmg7Iaisv?z5g(uFYSB*iEZgu@j=r_{0#+dK>=~lXZ(~;cob3w>qlIM0;=`=X~aj5r%!wj6hAeci^b)^Pa-gCqDJ5+gl#>Cqh5- z(LZM;ERd-jfMf9q4&bVE3_4Nmal3O(MOMdy~(LJuB z3+&cK-7D4NDG@)}aub`xTWwg9JSu)r;-;DP%7;LUT*$i9aD8tJGqPZtj?o-eJ>c`; zM9hLCF-R@r= zFOD-GYKU3$(hQM_nfexAh=b#yN?pxqTzrYYbWDzWo*42HqvK+tKTT*lwl(phjeXmh znsKOS10^??>mEc?37?iS=A5a}VgX>{1ug)TP6Hfs;{ zT*80m6F=VZVc{}S-{mrenc-tyPg`5p2MK6JU%%AcD!p28?t11N<*caW%m;Rd&tA zc;@%3nM-`{D*M)Ujmv2qz}Q4d2oVj=2~1J|Y?RQf&-1LO-`@Lt!-+aNI{ob3yZh~4 zsaLNK@4NT+9KDgvTnxYWNcS22j)@%X5byn23}}`t`Ke`s#6x5PS(WqjqTpzz8X=j%ZwSh_k^m2mlrlodA|o_ z4?5d6+Tc%o?49R0AF>DZ`H()u39(ZTk@`l)@m2h^^OEB7Mal9SU}o7{b=22eU|r@M z%0C~?KPR1URb|ISCm!-j@tHt*VccE$#GMszZ~s|z;Fa?IOu zl|-_KbbO>tL|rEUnz8du3?(Zs@-9cu+_tX+Vsy}&>wOe&*ejoTb#nl3*`^6vesfUw z;sgspL49wS_N{5uw@!feY&Ntf->a(>lK_`o`MR`rgKGR1)Hjz(pBItwR7QQEPu^s* zKqdjnX`7PN&uT}8Zdj37IWqJFT?-SFiKkN>-nIkW_Md4Itkx4dj9GtrL2mnVNTkb- zkM5Tiajt1MmoSSFPx-w!fN_wncKpT|;qyEJww?ZlQS3vX4_fhI+V8#RWxG2+`oDKK z-~1nUH{N)M>Hs_%L&d}9!!1GOT=od&nIZk9FB@_Czwwk52~nYQ$CnfRa{s)!AU`sQ zM`RKo@y&K9(o6J}BHOj9XRJe~7HC9g`H8QsO~q>W81NG9u*XRxWHj@VjXlPpW8CW{ zktN$3Nm){T)`naufSy>%9LN~rOLQm(n6u?0ZKN81^FyMspZJjH{-e*ie9c^Eyj9Qq z_D_}c6I^VndY~+QQ(xL2D5FW`9)|`^sh90-Q_7wP@YC1$-gR7W@!*)qI;Gg)A5!S2 zp|TM%WW}3)ijTuZUq?1cD0=lyAN0`$e=>eWTQ>QMakHGUMp9p*)ECCOY|ep%-^Fjf zmk43gjkL`>z^aoRv7Y%m!=hEAlDwgC|ESvgFDj9(#Y?yt(OYbVfi&9?kdEyG6 zLzD6GzLMB{aPQkYYF2ULS0~wb#+}KJZ*CM z3*UKe5SO&$!#t$coM|4Qvfc+etH7Fwf5*2imEvRN#iISWKE^9k$_ADjZwOvwhDCv{q&W}a@ZMrCw_uRb+#I4D=HYyF&o zziIFd1&ca=Ly-fho_J~#+ZI0ue!l)~d%AZxhXZbOaDA8pU-uwV*5Ina1fX@ILV4+x zP5_zIZ#O@Z$$&*hWg;scEo#a=aZ`>w@iqf?**>*2?WW)5%Ig|G<>?1R)2kNW^r-|)c{`yyMl!=E`c+jdW4`_+B2jpmb%hGZ50m%jLt-MioY zUw3bQ^RMil`OHr?k2u8XvFSuV>O~vx(4`D)I`kVa7s}P*k5<#ymK*s;Vz1g48?WVI zJM+;opbFV1T~P?y7WEY#=sK=P|2rRj=yLSAjy7GW45;5*ymjqy*ILqvjYDkBC*3aS z+OkA*fouH5{hgO7gW zn<@v^Pu_NtGzO~d_T!WN;Gd~_56fQ0P1&{D-?oQAe(FqIM%OGSI-M7Bo2eL-?e2GC z((NWfh6|Nw3QdD{%^&2ekG5evB&rwG5hL;SF|Ui{^FEED^kYuJ(BItw)QwnHzdSa) zOwb=?Nctq(BC8>us!Fx@3hSTuMEiT+w&Cxl@jsY=KP-cGR7)?fQZkPXF(ynlnI}Kb z;@eyM&GXLXBykn5=OTH>WtaDS;x`OMlaedt9}?BF7xnoA1CF@0P&}TIQ_cvc^g0IgOcPQ|oKdKyO{vAy8Mv?Hr_L zH|eAMMvlHJbFI|ZrnP<8JKHZn$4m4*HkA8XBuDTkwumX+JoS86d&Su3bJdYc=Y(Nr zCHA8c50#2o=4G9e1y!xK0DnWp5$=Wd5n}%G4SqB&JO-VjrK_l4CSj;G!b9}m@+qrDo zMqB9m&{l3eTb-z|@c=VV7n@c^%P+nh>eAO%#qgblRd|B`Xi#I)a^Fk{~pJPE!_onf5V!XXU zYaEzI#3TMFVfZC+Y@4idi)9~7^{)ZZ@9BX~dWRlv$j0Hi%JZg(+q5RuxM1)XmlW9KDdsu;l8RrRnQ@&>j3rXmvj0~a@+h*I7^1wk!ATQ zE3cR4Q^kj#rjEn6`$rs_rpBS;iF(v*x+T>)Hq;9~4)Ba+ZX!oqwJ)kL;zT}_3<=Y< z$KHI@M;}S!$%ChUf=+vAHFtO+(~6X}nW9Y+WP&(c=GArPp+{4$&mstafl_S5-!@kqjXvqGvSKc=su)iEn^K*@+W#32XYLsHGDvae1x=^f@S79>p^T#og2hYIcq;OIg@U2;IY>_JlP>$1S6rY zwRS)cEw;!Ypb^UeM>yPI1lmr=?Fwjc}(rs5J2<0r=IBgpY2u&OM zIXUPYc-x|2$Bn_sByOlgdk>%%rgCl$P6%rdCZHGCS`v7Qjyuvr@RI`v6S7IKFc{r_A zN2V4~II0~bym;etb%L6{mR(w(Jg3wT-m*``jf#QH%Old(*Y4lYVL9nPm6F<`ne(i# z-q8K+v-1ab_w$cJRGa)z{*V@_K_@wK+1$M^@UH>+=EmPH&}ORsfJY|SHp}r^kp5Eb zwhhz+>zq*6ZI0#a`Nwr6fQ0;H5MNW__GxVE71j1*>y}+#}g2R(J!FLGm* zy*>wYnGjixO`>IGUQkwBePA&x;^)<4El7XjJ{8o}xuxe9@)&#Synl(HgfV88=lOm( z*QrBKu94q))3|>#9W)!TE$bnM$<8i&UOIUVaEvmK{LQ21k`L9;+egtm?@yx-W9@R% z0d+P?x{c=CqYth7>jYuS+N+u_ZK7`;(N=lxoBf_^mx1jgPLNmUJDKJ_#!eS!zac-d zH`iCfCfcz>HTyK88)dhP4!^3r@!OxAS<5f&)6wT3GU`3zmi|?ly3nhi+QYXwfdTk} zao4)k>yvzhafM+^%SenFv3>&mqPFdEv0iPH`dwv2sHcb$ZGBAOlDN%{Tl^(p4=mZ#z+D zwoJgKubQ_96TqVbC;tjlCFErRV)2>(n3;u08#*@1PUj%<)FzEv8*sU=tE>ZU2Y@Do z?5_5D+b>(P_0XGVmRl4sjBzJe)j##svhbNMiVt1|9&!$30qLtZA7rx~Y$9rEh!c}r z27N*Y;FEfi#clFZ2DIB3KHO`8sPV{x$j>gd2z3m4VIU?twy~>YNs~t6p`mS~8TvXG z9=0t23b&d5?z?Z^edHtmb9eJg|MTv~8$TlZ(x1aIaD19?K%%MZd{n9+AVP=hhZvLe zm;P7cy80b{ZP;vr9h<&^u}2vZ z5>Qtl5H|VSP3#859Yt1L@ruV#C#yp3_ zuX6Lvh+UlqKg7_>6x(B(#NhT6a9)3_Nlc=xlI^Ob`j+Kd*B9UsJ-*Sk?Fe0LN*b8! zEpdQ4`m8ml`=7E7dd*j6m%eR$z*wUS?pxcXv2)B(ZIdI$FucVo&+8V^tW2k zZJI1EX~a&+kKN&;ubOWiHc<{9*_<^aH)hyL-<3vR3uMq$ z(wJaFc$=TsCY$o4XtJryP+Ve<d4_!IdKlmn=(@{g=vWApmGN3ADj^e^f@p#2$JKK#+!vC73}u$xD#wI@Uz3ic^5!G)l`XQPbM>L) zTvk9^^#MgyRayNgNJl5e&AP0c8=>27|NnNceC03hp7HdL4m;t^SR+)|T}MKJ>@7JQ zM#lW9H0v96q>j({N+{X3Cw^@Hq8%|_*X|Lr%!4htf#2eCvt9k@>w3#ydh6O_>ni6U zZP~cxUNY>%r`-;?)`mf!+GgnBPyNFC`sU+R*Wn#98?npl0XYeM8?WiI zUPGVwFpb{Dfc(rUJ(#L%+M3in^`@U1`%asz#$=yLvYCwB>j3rgZOcNg>5fk5@Dt2! z-Kgr8)Q18k_XET)$Z&NKntaR!$;)kD_gRTxG!F> z(&l+o`r0mRI@BM%i3{0KdCFUA1|ip5eR)87Hh(zT1|Lcli^!@MZ}Ewa+`i=+de?1o zES_=eF^dnX%|7XV7agMKeh`D&=lRtO4~QxrJtm@*zO5rJ@9C~4SuL4O7xbkvWHi0( z()vTcJTB;o9Q0>>XT4zE&|cU+(xG_(-tF(#@>59qeF(|!Brf&A_NWfK?5g_X zU|DS!zN|Fpk;@B3=y7fHSSLDcZ@#JC6773qR4Hqj#s)c)yxA7<9n!S#xRy;=G__Nw zeq(Elr7i_gZkXqM<`?nD!(IPm+Ix(~fxh%uGOqbX-SI}BNJ!muh__?J@v%Wy`Y=7b z@m0>XiIpUeMWwcz>(P!JiQ4oy{w;gU`H&>_33*f{KK-+9$7X0UZ<&*h_iyap`@RpJ z`!_;xh04Ahg zYC#n=b6w?@M+a;xbqa#=O@arS!B@HZUZ7qa-Ik3|!9%q_Bs%u`FyKCb*n~_^d}Mgs zY*zK#0tT-dkdFA~m%O4GGMb8y#FaM$WEWr2P}WZ-_1kp+FUq!KlP$Z;|5@ZU28uu9aqc=u2$Xi@a^7|HSotoy7n;kG*v%l@4sTFTF6MHrKWZEBH9n zMZDwN_JKa?Gq#On`>`vF5_QtiefI*rC9MmsUp5q74zA*F{aLuPkRg6UxZyF)C~}*>_q`YTSKT z_MFh3iC?g}do4LFAOEIqYooj&ZSuXk?c9EF%-Ih6i~2Dq&@BPxANy^!+lQMy@sIss zJ%DTZqT?Wc>!x^R&WN)8H{_95-%3P$K-|zS|Ir=}(fWogWfF*QwVv>8mikG*DzAE| zLYv(EqOfJs#alF{lhvU~q3UF-<~+IoUeY$1fBegYtRH2w*5tN_T>7AwJeYhPNR?#A zH|`S&X5<9fV~4!X6Vup6h1NEeGiSY~ZHHvbFx)Tsar9GS^fA;^@7|b>F_4{`&6cyt zBWVw%4qoJz?y(M3F4~UI$dF&lR{aFG{~;*;iEFLT%n^7oiPz9ocJv%Wr)6Qb=PNv* zJtrLjbO66W=QXk_$SYHG5h2SdeRD1WMVNkVfHT+5BSU;#SE2=b5R);m{jJXyXiODr z%s0}cD>Ol3520z9b-SHwHOTJxM4x@FSSnq3g6qA++y%(snsT?fa?^Qut+=LKFE}-? zAb{7T)=`PJTW|f)x!(xA{q1j686^_h6fzY(GA22J=Rx!Y8I&@D!1GOlCt3zWcd$CV zctDT?)LxEbQ2^Qy^b;FyhW0ywuINM~_GTl^gp!?2PnmihFm&k3%~pS%FI$k;0Vzg4 z)G6CYsx~bQvXzP1lbghA*y+WU-1Sbnrd)$!Tj8}z1%cFby8;dteag1zCVA5_pL`*r z<{vUQ-y0n`@Q7br)+5`@A7pX`(We5}`aBxpYEq;lQ1Uj3#-@YOM83<=>#~G+d>k*> zl?g$+Cbr)bEK|H=!KdF6Xn9;uT*&rj+jb(q>*qGJ*q56>EeQ_BjzbJFeAit!?>_Ls z|Gs@aMz4=a|P+;e1` zQ|6@~n~d0^B-(5Yrqx16|9gJZ0N?Bn0lib6*k=6n6G`ejc}zvDOmetH)?9W;&<0tF zwZk_DooDkaNbKml`=j-u%G9Ax(nq^WPfwE26=+<4QU+#nLuquhS;KR_TOrK1h@Wx?ac8tn0t zFUxoSHp_<&fSuSo1Ha`)K(E%ReyeYtw+uR}zSqlo-RH!g|i*@n3C_ z!9gxB;j`%ET9|F##!lcGTJ?MLg`}1M)*9Wg%QsSH6d!&piCWi)qY?8ox4!gI2|H-@ zdx!$znSna$JZ4VR$=~^AM0%~qJdwKT%{8(#hw3T^;n<04(MyN_7q|!w zd&)+`S{FLa=`lVo%O=W|Oa4qROO2{ko^`=3l~*5zJmqSjY0z0uUmqsXhN=634a(}X zl5MK~(kGR-L_7SNtIRv>>G_s~9%$vW;g`+NlGBhy^;Vyn7eJFas`a_oY5qxgp9wjC zNkGdmpLz0m?uq*{b0M{*UL3&YaU(537N<$s+A;AkA?4%H%!)7o(oSbW3bpsLttm>ilQ zHE8hD?!b0n5G?a=l)WexKcdKsC4(&8!-nZvZ6fiYvWbiUp`itl1t}*-R%OE#SjvVG%2O|XZL|G0a~Q*OsP>59)RyLGE&r_c5YFuh7@^Jd-sDSfiN z?Ptz!vB*5A_=KzZW81Koiw1n#!d!{@O5L#4D9$cf>}anHd79HK{?lPJusX)py5QBr z6vh|(B-?h9voUz=V_PZF+y0L({hdRV=|A#;NZYoQlR(zDY_xz3-J&Qu`J!xKEvbqj zXZX#c?Cb82h++c-&Erk3`cv~@zrWTwZ}?7XYKpe43v+u8Z=^u|>|9nLdC+UX_4+oKpH}*(zo_v1vTVjK>${%da>Mt44?~fO2_?~Xi<6?~q32@%ttI{_ z**P=-tmlT3C&H4?e}2e+70@~)xoGvTpw(RFCnWj1HgBx)jl>DIyT_pXfD*-*wAr>T zd9I;{Yh&w!^VT81IL}Q1FZ-S`K%aHz#t+})b7WYDB-X3Ol`*J3AUoy6>!w?opg#3{ z(cX+s>W1zjqO1<__GF;jb&ecGQ}L5VH#vmQh`tRKZ$;hxU+4E zhx9+|f?|c7b|lw3_9RBfn%Q;3W@$Dw7Fy?g(~j-PRv)S_$YsyupPbMCJ%}tnz;Lo$ z%Tr!Fo-a;Zqm(AvXM4u}*aX!b*_8fz?zMktQ*Qro4Y(Gh+&<78Kz_x8&qmCFo|lz- z4!69>r=mW{5s4h+NsjtxpUP0b%~PN(bU`*uX|vg5wvVE5*2s0~u0(FwI4nhk;sPJZ z&+RjGkhh+B9@bm->&Cl%fMk4tK>37*I@G`u^Sf-uK^j zuY2t;@1F6DkBJ_w2x9yq16s*Zfwv^6Y*1+Z;v?e%6g9lF?gmwE*QMKXG2nK^Dg4!s zP)Ozk%{BDLAN7Jli(JvB|Mo@6sd{x+%)D*0>_g{A zz-L?$inD02V z8rw}-?C>`)*qej(k-6*mv~6A!JT~+Lzy^=ycOT#@I_4?4Hl>o|K8ehEA#1B-=yep_ zXT^bfwDHFus#RIkL zRaApk@{8Uwy%uw=)G|b~SH=$8Gi<5rW*Kx!#Me~E#TZNRki%t}87JzqFQ^R}vYU8? z9@(mKYrS(gkZqNuSN%tC(@JMcv!KxiXri?h4*%(JNuy|uu#2>5{VxYP?js-jq_=F# zo}rth>YGU>TMDSb2ij{m^i=MCS(X$Q=J`va?0S;>gpU|^(M@I3L0AO@%SLMJL)Dgv zF#MOc*rv3{w;}cb`XasMW|fbT&LJ`90A6MGmic? zaXRae16fgggp*>cSZ^4~RmaDNuMrFY3o%@@yRTtp1yrIOm|l-kTInu29pk^6$o?qm8%eE}9pYTsG5``d!mt{7+?PTf)k zzDEBr_#%*igB3Ah&W}vcqG;T9ExO^W?m~5qjHO->$M1*;uFi zQ=~QwC{tahy4;)_N2|+vLtr`;Bo}NtDv8eyQoG)?nO|}!(rI!zr^<4`G)dYfJCL%t zDj|)``lN@K>>T2aYKIr*1bquq+m_ir*{eEo>vDc3LLVNXNlQ}-Dv1_Z&?~30`8HC4 zT9x6&)~XnbMJMYtzkM_Lsq26!!p{Vc3}QhFcz4iM($5@t5~hFr!T*nm_=_h`d9>&x zwag%T11>SuG>nDyAe#ii;KA6oNBv>3q8;0shJIT&3)NNW7FUjTrTS|$9|gU%`~snXUQplA%}iSNBo&SBaPa6)is-e)Kuj*79|h4tyfau z<&Er0)WejR+|a`KtopQjAw1frTVFC(+hR!kX|p2LHSM~wM_!ew*8!q8Hp_+9i@fDQ zyOqyKYV6IebyJ6o^xKu#DM9uxx=ZKqZTcn#uS-dQHt6$Dq`NSwmbGvjn4SS z<(66U$eP@TprVuhwj&1*9%hhaZ}U|qn*epRJzT&pzo^AfD>QAGeMUcB&4=Q-QfQHh?@dtIR6j$yTAl$PG|>7w`G)YA zUxt9_nn+U?MblwJ5@M?)!r3;{!{UApgq~uPJ2O!ZYUCO#;+;L2I27e3jIq;vsjKf`N{K_h)UzO8B zCU#!k2g_#uSl%IGi_7{{*?MD>+k8+)r`Mcu@aEvIy$AOCXd8HY&9E(Kmkp%Cww`Xe znE0&B~VI=TEoLhzKQV~;<@4*2am1SjriQ_89qcFZNz|op~DSF(e+_e zYieQGgRd~8fz6xWR8vV*RWdJm)_NMCPrG?6KYbc$j^WlRUlyP25lz-R3v!t?s><{` zeeW{-JRTW)FLTM9-Q=X627QilkrO7&u( zHDIKkP(bEMW+u6+#S1Oi*R3k^bWxI`uM$vO(GWCxYJ#&mmz*9LQ&--DkO?e#-G*J; zV zBu}mce*ZyuQf^jSj>gay3>(}h^HQY+7h37%T9v%%rRw(3^`@)q?jmEM#T4F-ada>q z9(%_!b$e(T_ulie-JKu(U%Q)c{?EIcZoFg24J@k?e$bfg`++3A=$Funi>Vzb!|c&# z=2I`^O&42J7H{!*oEYcC4GCG+CD|p(nLdR%*0Q({z9NG|I?xwB+AHHqIc?M{7nAd& zkhYeGNSmk+Vd!b-O0shim_PJeKivP6x4Mq!DvQ25LR(_g{>tVEg=uVS$7I)G3s$8~ zN%32$%F-b@9t)~;08v5B0(|p1ofLaEu{if9uyX%JdcSD)Z_(Rr5h3oRX1Lejq-TdprhAt`AqcEoE$%4A)kQd@|Rf7ypps&vD2k znP9W6SZot>hxl;paKO!>-Vc0SFBz4vfH7ikVjS4aZ@9rfv&~Nk(TxhI4JlJDoyct; zBp%6!4W*lFv(-&T)z9$ZsO%vo>Xmqkjr33)5U~50u4_osZ|uw8 zPI}C?^Oo#moW$>kdgIVaJatT|Zw1Z^{^bXU^^9f5M9G#f=$pu~A709_*=G)TLE1K3 zNvx@k3%x{>c5F9Od@!d&P?dW4U2dfX_se=?!-zj#jD7Lg&mQ~qJF<8Ms+!SF)?=iI z966B>lds$65)eDJ=1f2BPaET*zST=>TFK^o$pfyh zfBn8nU)N8I?fa5jv62`-=6rS&$g3~dru8VGu8RRYb8;WHcpiP~{xnyA_8jhYLu+rP z`8@po_rLetzY%)F8{Q=2g~~%9XLlLQhSMN}pzncEf?My%bD1^_oDC<1PtuUP2g{$4 zgMk;E@Q@rBTN3$RogCY_9b~%A20*)=pG9qxS2;RGXAsZ~2>R(8ax@t9PuE+}g5-vE zNn*WY2PwX?%p#?}UV2j@o0_+w>$W*x1>1I~fTH!ZEQB^x8Xw_1lNMXhoj}bbhEP=G zq_W?Wo&a?nfYERk3 zid9)=h>sUMxt_}R)Q!;Xd?R$rf7#viRQ}bt8pr0}`lic575rAcfpld;Rw>=0{(f50pd+i(KkGeqIza-g-?oGxG|^KzSz#izzDkOZwi(swoBT3Tk4u%)Cv2G$%3_;DG_S7p*%%j_ zT~tCUzriP65-C`RHvoL1pZ-)GqTtConcw|yhfri}cA+yl&Dk__NU=Qg0rj)e_*+Xh zn<1-_OYCl5K3(0L5p6xMeQiA&`>Kb5>k$Ve*ejO}%vaVb4rMw#&%W;1Rcwk&z`Kl< ze1`38=o6phQsy#jD%%dne|%Zxu7f0F9$C?k7-}TDX?!rqxb@RYc*QA&sO;QHSCl)4 zK)TxIxjgKs_dJhbwhVa7j)^wY1uQ0|4puQ+!<(hKzDDJynwB%6&`a13NIIF&5TNjdApUA6A&r|A|-`Lf$ z*|DMZp>oP|z3m}w`o{TyRIkj}^xrm;F^2RV`nGkPEul?r+3;~``#NFAL0Men^;V3M z=5s{BdE{8M6CV;FI_3mpE*+ZFZh}u|uygOJ zitkk~D$|{jM!kKbevs6Uwtu>gjcsyalOek*k3#6&KU3Qm-CT6;i_cimVOUoB$~u+v zif#^Dk9ERrg`fHK-|n9Coaan(_HpEm(6gWY?G{+6tPpb+uLzRabXu7^lZlgSXp_c5 ztXVU>Vdto5r;wPG{)4CHBd>ZK6elEUkt_b;WbBE&zL;fa;TUzg%C!okzO6J$zQlKX z5QnF1GxSj?S_KRC`&WGav-A0r-$1G>HO4x}0V|K$JUk7LrVA*<1wBm`}tW z=ei)LGQmCii2f>j>_{Rj*lu{KP$mV`!USK&99bS~2Qc*33m9+xbV9!i<~PaL$qw<- zcZs!)EC7y8UuV*1QQ&R$)+vnZeL%1JsVRD}4_n6*v8scEzT}{z!%iP~W_S}pMy~zS zxZ7_1mEFr<{-69Gs_GxbP{-8nga$Kd6KLOg{I=`E1g~u~P3Bo;x=sR6Qc5oV*6CX0 zxFp+nRjxx)`-7x^;fJ3?Rqi&A=YFzG>p`bsbCtJEb~^-T!yU9;P68J1@eE&R z_dxxWV<(=dOXYw%#xGAK_ix&_ej)#8Or70>dF>nIMyA^~JD}-YA7u|bWfKd&z8Rfj zQ#Y@bE0wJ<;YZ^0`s;7dlRtm+y6-pqtT;gj{-~q}F&#%;J(aihdbXQ>INsf#S)ODf zuh$jyMxIdg*_cU=ukv^QJcmAIZG%g;%kE8X;vE9XZsMv%LtR!y$p(tC?)$JM_F%)D z2d+%!(v%Al(|xWN)nkl_rINY%2!_N@^N`v{t`|wYp>G+A7q2VS1<+V%(~c%z17v#4 z>3{WI{hxFJ#Dph8x;b`1KE~4xqBUP#hp#YrL|b&w7Dj)x#?l}6jh|$VIHn9umGK?6 zNq6?Pku!!QX|%r90}rqbMcehN-prKA_M0n3KiMnH^nEcmi@b{fS=p;J?u;FL(IXuN z_z*;W^X-HF=uUp}eihX>OE9d=%dw<&H>f~@|q zpD1Hvk{ij@nmU$_E#gSOx`q?J@P{ZUMC=GM8!ejF?ttDwtjM5gEN)`xBWdW^DH$}_fW=o={SXEAJdd(M2Wg26xWzN+Hu8Dyf5BVJ1&{t=z+itz{+`kce&1+sWIyWQE zBPSs2eBLgTyeX+W!IKSMaAfcu7?xj&SM(J_4qKk!RR=!}^^Py{q!U;tnx=Mg zeB#Qkr(Yy!t&6fZ4|v=cTG5N0*rzu2pTJ5Gw$>u{B9QjYF4{r*FL}klOO}PKV4L>Q z){A~7cBvPshUIPjR85yho2v)x?@HL^8ucf3&t>x?&xv}MtKZe<93~*gt|8k(_R3%U z;*0f_}D_+|1>>y0k!Lq>e*MZ>=Z=I=6m5Dvd-kTc7p3tQ(m*^GJQ z!@KdNZKEwZa`@rtauw9Z*ptSMp$^X4lP=icb)G(It*snOd{FWFv~8$)kcZCt z?0y`F=$3sGt*%wxdK@XPM>hSmJ)td80y4pT2uqn3nl~MVE=!B@*e0p!D=)pNY=|Ga zDo3`M8nn+bZgTt0@*~$}+ll`QRW1Kg*Yn7vj8)Mm#;~pVfpu=AM~ihNM~(nBhK zVy1}BpeL6Z^+8OjulON4Ji@T<@p284dpxRMHjqqbV8{Mi<8n7QXe%!HA?qnHJ$&v@ z(~KJ;+14X{x+8aNkgXe)J4n_y~l!>)J+NFQualL zEtNT;MUu2JNFx*H@@l3SZ5<+Fq5J>SC_q5 zSb=~K{h?g+yc9?TR5?QOaL9f>JA>|EOoEU)Dyp>QsOt{fhRR2WT~{BHMGnion`cmy zTi@;}N^nP-*#eqKL=?6g6c8Z+f!F|1Aa+3MLC{SJA#_scy{K$KibQN!XaS^1hd@9e zk&W~qB|zvclq4kN9iQ{=XFuni^X1H(IoG#!&-$;qX04euYyGZ!>2b*7>)bFP-sm zLOMW-I*wOc{(5$d|0w%*)@%>z#nm+v7Fh+?SpIvJrO>b7O@*}P7s%aG$uIS3@xcSJ z3nh_uNO4=pZK!>PW3c0buBX#QpSrgn&mik!Xc1o@$l%ueBZg7aRZmFdY@0tET&u@% zVAxaQM={TSMu6L}*`w>k$| c6^H|r=8l|DfTk|&+;cn1Btc;s}H1YDHc zr$Y-I!?TxZ=Y+!1ZkRBC)Dkvo>&N*88Z@aIe8Kc?yvS4S?e2QU%nj+V!FdmH)Dx2- zJnfxp-Lw2U852VW33KEBEM4hQ^YuYdcUS$ft-OVSIpEd9^#j~edChXR$;?1t``2aLoz zC>(5;Tc!Lu_Hv1Zv=2Saz^dX$KX`gSlSG=v5qh)v6>5eeK>*%l*plzRxA z?lMgwo@ArKRLzc8kJ?Vs#FtkrwZe~yM z5yAw=-yi-tXi0B#R{HTx%-0o=j;@w>65fIe=COUjkYDVrl7dfJKx=bb%=j;5E6CF3 z$j(21^D|H6nvR7o&Px^h-DzmuW3M*!W4%-!$4OyV$%P0!#JIwewX)hvaWxNHDxrY9Mv1Q-_h;nJwz&CS0w!P4xYfFQ*0Pt5 zD^KVb+^l{oxcdQhR6DQsz}a*o@#-{tBV!(OU>D)faeK0P43!^jecpOwN;UaS_SYg6 z{nI1H!?P-2fJbm+^(7gE5=(jlZuWj>&l19)OwG$~5ckPGf#Q#9-?Gt^a@tgi&+}X|w z#_V6X0_%+lv%bm{?cCp9)eV;}pX{3mfLJ}g@bppoh~0S6cfjC-y$8>m5(8K|)TS*<#7 zT^rR`TjEr?u<+_@=z>*S*W#BSW}Sf5*P5o16{xAr3#79}{5^b8`i-HXdO$_%OK-H{ zsViqo$ski-BmRxsQ$y7D6L-$OV~Y>GDpdZ}@`XyrBfx94&&_9@%@03HB+U2>y$xP^ zi5^5E;*$l&bDl#oT>g?}A9A7J*>S7hTWM z=YKSzo#g+Y1Nrnhk4m1>__yr*ZD1FH|H%4CfAY8He{?7I|84n1Rz?GVS|-qzQ`4|h zGkWgFT1vga5rmM97&{@pD?{Y8;6IQ2{3&Y8XwDotug-)K*|3`O5}$w|&O~hB_GsYP zauWc0J9wfQ)2%zOsI*;0T`FqW<&DDdy&)* z^I`?ZTF#{7X2@syyKIBLGr?n=wq*~;o#EwhfRYWc-(*icC11FO7OFxub5af_T1(vZ zbX2^X<9NshLm=3!;U74qti&pXy!X&F{y9mnmA1!-!g~d$l~+$0JHU^q%NJ`D3>qT} z;0>iElYBs6=@I&iyE%@*RXG@fUKK;z2-Uj%3^2KKbF|h$m#DJQg5bB*L>>lHH*U<6HSo_dNs|D^x z9@|+1weO0P=)_%i&365E9o~OA=m$GDKYHn+YtE_q^=HL?k1BUEh+GA3V)5sOrIC8C z?Pi7glKUxb2!0DQtVSp-DhWB% zzy;%!rzRSzcj+eb94e7-)@tM%zq7*4T{#4Jyj{0~4@C|H#kCCP21IfPh=PGEq9%Us z+Cjkha?MKr;J5;TD)?w!H*cd~@VTopbfwOkM;r$b#@mgxDgqf8>hdQ?!AF;4>o%H) zLJ6vv7AaV}S%GN&kd#%z60CvSoq!HYE&wb_@db_15nyFrGiUE$r<4E#xVVL!&AcV# z6$?XbT?FspRLud0(4|A}M#n3QaB1Sb;lo@-Dkq^_J;Du0iS&c)IeOUd~PBJbP<{5V;w|lLFxeQs{RfQLcU`9nF>Zy3C4XMsR=Y z%03hel6GEAvkDphn)kGIW+ofm-yB^CY4nXlt)W`#rql1A4PTYQf4QfiEIe4%7I`^Btj-sRAF#xYi zuIQu=`emlf=h*h}IDk&lDOfUN??P!+po`rw&rJWD-6x&Fwaxcn%u`BLZVtvER zrTC&ehLX&D1V2TKKSfj8h>W7sSP-8qX!S`aNIbi};pgs@vVz1-g4V$@K~Unj<9FHoy2w2(x5#;6OUp~N`5Lr`6JO?`hDSaGW=XqD; zaIOIgpg-QB^`PyzXy~sqCW&g6$Ae1N-hh>JDJ8QnK_iM-Jt}UY#nstv)d;8z)&_23 z#;zLnV;HIl4Qn8P$z-D9_&%FSBTN!{?ZnvQGr5$5m?XzFqlK%JaE!JJ#@r?8TWh$! zcBk_MmB^?12Z8MhRIh#u7C$ZpzW z8;a7T8rCfZx=|`I83}QE?hX-)H^FH$FFxo2^rw4%>oVarzq4Yb!B?kLqcM|nip<8% zTK#c#&LJvyywy2e_fO0vZ|S(fUrwP~hlzhBU-zUcdBW#SC55F{d5QjU;$rJIz~HA= z{F1vMU^ysz79mA#)q5@zHw2zliS=xgz-xx|B)0u%6qOj|B<%WJ`O53iHNM()Bv2)a zah&tg87&F*IOm~)f0v359U1u^z{q(;Wd8_5v+BZI>|8SZbBrf?nOanRz%M~o36^c@ z%+4=~!juFy@QF#zrAT4?zTp{oYz&-!;i)3iO~S~IjtREQVV7*Yfx8piGV(_ywdIpU z3C7>M;l1doe7xzb`GzR?rO}&nzYGRL4zM=D{bhxvnrR%jh|Ms69a!q1siP?Su}w2+ zYOvYnfsy4R+fucDI{z=qsRfPFNjl{$xzV2{&q@2N&>*rU+Xf2RQrcQu+?%9;mAl`t z9ok?`Fjd_uDUt(mILD9Ii{hzPizaH=XZ|8DrUnTNo6`Ied1nwa%8nN%H8mKW{D_`q zl2CBG-)NDVT9y(mHB^=&hOxk<#erNj;7g{nvn%mR%%ev$gY@@^Mm%dIZr6;}?X)2H zmrfN}aKiSkZxdFw1BkqQ;>U6K$eO|PYLU@|Tv@jZJT^jzoqO=IN6O|hoWGVyv1D6{ss3frW5&B{sUAHo{RnOv;>I`fL$WQu2P$~NZ+{gp z5Y@x>nwXI+!@M-CG@f^`F8x}*s<9ZE98PI#d0wjcV$UQTa~{G{ z%|ZvpY3ub-)}kYV`3l4}g#=4Ib?LVhRcr*ug;v6G)**MjGXo>%2QApg)3Y7*^2$cT z4j^LJo^kY(j5g9z5{iM(S_id+;xlUeIp727x>?CpIao!PU`X{L9ETB+tm<%K&WMD3 zX!_EaH?=CUPXIaXi|Q1W0&7-S4uMzA^=^6_!rwQrj8=L=sNr$3Zflw{TcrdSnFZER zThGw3P;qR6E+UrRb<#U$Rpw~=5SSAaZ{yCNA^BUgz)I%e%~;b>VXjH z+>JxFU5Av;bT!g*tb^XSGA5FmhK)V!*w=iFmTab{wK)B) zamwXFv#NYzFzR{J)YKy$l21YYMjnbxUx7-+`6wbjsF6k* z8OF?u56E1$<%O9cWdUS6Ec>R?z15eoEo)TcEi$O_gk2y&RxWTvhZ)R%)2P@raoB)0Ori*xR+ z>O+PMux}XEq5f18X(Jr(@&gPnzZs}Uwj$=8OX@C2izQ3U4CXxf^4c}L*Oja($Ewad z_Xd#-SIZT}(8fs9qT-v3$5Txm(P7W0ntu0qK=}IAL6N9q#kfL84ACl&>nPsh!Gymq z+zfBgm&uki%hf&>G`oOdfVL@8JRmn&~Y;bEOB=R7+fy5z_6gm z*fE(&_Whxaie)L6uoaDN-qO``5gBU}s{8F{Cq~9w$c9&qLm~BCV;=<8s zrwbA3di6!qEV!XpjSYBpzx+#!hmZHFI<>T4o@k3vOC@JS70&f4KW>qDPN9fXH>GT6 zpEu~9+sDyzR0nu|YnL1>mr>Zcw$C$5kSUcBasY3*0o#2`aE2zS1ND&;L1OKujj+pR z+<8wX$A!bazHH8pPR>O*&~eU8{V}vkJk)29{vFz;^nAqK&cb&5F(DfOb>+yKuhpDs&! zp8aAEJGtrYo{E>T4SOxS#>;~7$A7qeYcq@rND-8YlHsI-A_HvhgWU@0vEx=%XfeAQmh&Apn-V&YK)QzQ*E=Sk6lN)T zs7aarR)WU@>wnewu94Nj3eYnTlD9I|OGw--q^XEbKCW&;>Yj0o3zVm^<2xxb+926$ z@zC|^Y2AlRDjpEAQN~N&XHyoeBx5;R5Nm_D7&?NM86{9f~ zcguikuth_%>GIUVG+S1DQ}rowX5?m4n(Kwo)1@LCl;HFF2GXL4xvE`OhDy z_)d~ooVai6Ih8G6AFe-#1|h}PT5Vd83|Rz+U*$jjo;)>Tc)+#8U-aa z$`A)6(uc%sHKL}lhh#Zyq_HA`u-z>YUpM%)m}jmLWN7aqJ{}JTL?>~ZCE7AE(=1TZ zA$AOW;#<($u;hg5X5@{y2M3T|Se+)MF6R(yD1zg>bo8AK4utsL(?;)mZq1#$;tgRX zpQ*ZT>sj^v#PS4FO)WlD8v9*zUJq{GRF`OON@6I z=CD*6i?}6+hg;6zC(wId#gblYna)!6q~$!l!u zFSA0@TIaOb)_SrmK&$abW6%V$5!n_eC?kUo^L_Nl9R>;BZ40Z9fv0cFqiBO&3p)^2 zd-wAr3M`7;5@i&^!qpg2^^H|%ERy~S2V^2v`pZV7@pUTw#1M>0E3VHYHlCp%(SIZU;~@ zK*NgFgXi?z#0`GY$Yt?TPfTrBKs>pHh7a20O5!lHov+#_BaobypxoIrxs307A@Vj| z!D8(L%ncn_2oU@n>zTzziT^w_ez0j8;B4A4mwc7UU8)^paJfo|UuhmjGF!&TU3}Ln z)$-5$c8U!7834pdY%%mW7&0Vl>yeU1{Ih^E`Ka_c*0cS>q%m=ulBXOSSr9rqk-9vT zqd%o1BeK+`Ed4kvWbx`niP+0Cr=3tN=%@CvZ`Wts-Qs~tDc7OjXt>ue5XNr12OQg9 zY)-LG^mOD!tThJ&*?7PuS+aQTaG6zI8Q;gQ z_L_{$Rw>L0wRo%|sL{XTisw32pw_C&45`2nj7zI>h2%Xmix3t?a{VRZcN(@GP!7s2 zK#fU`;G+OVBX!eMl=_g)+(u+)Uf? z2l@FQMNZ3~KC&J~oN)a=S8l)M^)DvW$la^rJtqCGVRv|ZgzxJ5uim94E<5~^N&eU7 z1U9xMVMQI7bcaxnKUv}(C9kyEZvDz4idjEw2M-*-hD$(aIMSun<%{2KQ^(W3= z9R9b>YtdArWlYUa3d&1WMORJ46xrJZEl%9nfqwJ_ZTy6ufdlq|h1oCvE-{nLseu#m zGdiT9(ZDgheNBna=0p-$Iak(@zxpHNa>gDUsN6eD{=aov1|Ex13O!E41A!Uhi~&1r zw=Ujal~yGe(hSO7jbprA#a8`2c64WKF@DKo!SvyT_C5l>4d1OlDv4);#|H7sSkl7( z9z*=3%L-Pt`^4NCl4}6JKnBLl(cWP7PT#-dgz1*F+>JN4WDtjFfm?WNhrH*&h zPZqlX&Z}9eukko7mAhHsKKIV!?+|0+34oQ>?9~iv;<3sUl+rlKW1Qq$ zLSxCCHKF8QoQmJl=YeIygaRSY$GD@2_efWdmyIEMmiga9#wGK~ZEnimlf5ivKhx?FV8 HDdN8XyCl<$ diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index 79eb11c11a..ca350f182a 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -488,12 +488,17 @@ - [Versioned](msg_docs/versioned_messages.md) - [ActuatorMotors](msg_docs/ActuatorMotors.md) - [ActuatorServos](msg_docs/ActuatorServos.md) + - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [ArmingCheckReply](msg_docs/ArmingCheckReply.md) - [ArmingCheckRequest](msg_docs/ArmingCheckRequest.md) - [BatteryStatus](msg_docs/BatteryStatus.md) - [ConfigOverrides](msg_docs/ConfigOverrides.md) + - [FixedWingLateralSetpoint](msg_docs/FixedWingLateralSetpoint.md) + - [FixedWingLongitudinalSetpoint](msg_docs/FixedWingLongitudinalSetpoint.md) - [GotoSetpoint](msg_docs/GotoSetpoint.md) - [HomePosition](msg_docs/HomePosition.md) + - [LateralControlConfiguration](msg_docs/LateralControlConfiguration.md) + - [LongitudinalControlConfiguration](msg_docs/LongitudinalControlConfiguration.md) - [ManualControlSetpoint](msg_docs/ManualControlSetpoint.md) - [ModeCompleted](msg_docs/ModeCompleted.md) - [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md) @@ -522,10 +527,8 @@ - [ActuatorTest](msg_docs/ActuatorTest.md) - [AdcReport](msg_docs/AdcReport.md) - [Airspeed](msg_docs/Airspeed.md) - - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [AirspeedWind](msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](msg_docs/AutotuneAttitudeControlStatus.md) - - [Buffer128](msg_docs/Buffer128.md) - [ButtonEvent](msg_docs/ButtonEvent.md) - [CameraCapture](msg_docs/CameraCapture.md) - [CameraStatus](msg_docs/CameraStatus.md) @@ -564,6 +567,9 @@ - [FailsafeFlags](msg_docs/FailsafeFlags.md) - [FailureDetectorStatus](msg_docs/FailureDetectorStatus.md) - [FigureEightStatus](msg_docs/FigureEightStatus.md) + - [FixedWingLateralGuidanceStatus](msg_docs/FixedWingLateralGuidanceStatus.md) + - [FixedWingLateralStatus](msg_docs/FixedWingLateralStatus.md) + - [FixedWingRunwayControl](msg_docs/FixedWingRunwayControl.md) - [FlightPhaseEstimation](msg_docs/FlightPhaseEstimation.md) - [FollowTarget](msg_docs/FollowTarget.md) - [FollowTargetEstimator](msg_docs/FollowTargetEstimator.md) @@ -616,7 +622,6 @@ - [NavigatorMissionItem](msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](msg_docs/NavigatorStatus.md) - [NormalizedUnsignedSetpoint](msg_docs/NormalizedUnsignedSetpoint.md) - - [NpfgStatus](msg_docs/NpfgStatus.md) - [ObstacleDistance](msg_docs/ObstacleDistance.md) - [OffboardControlMode](msg_docs/OffboardControlMode.md) - [OnboardComputerStatus](msg_docs/OnboardComputerStatus.md) @@ -652,13 +657,12 @@ - [RcParameterMap](msg_docs/RcParameterMap.md) - [RoverAttitudeSetpoint](msg_docs/RoverAttitudeSetpoint.md) - [RoverAttitudeStatus](msg_docs/RoverAttitudeStatus.md) - - [RoverMecanumGuidanceStatus](msg_docs/RoverMecanumGuidanceStatus.md) - - [RoverMecanumSetpoint](msg_docs/RoverMecanumSetpoint.md) - - [RoverMecanumStatus](msg_docs/RoverMecanumStatus.md) + - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) + - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) - [RoverVelocityStatus](msg_docs/RoverVelocityStatus.md) - [Rpm](msg_docs/Rpm.md) - [RtlStatus](msg_docs/RtlStatus.md) @@ -690,6 +694,7 @@ - [TelemetryStatus](msg_docs/TelemetryStatus.md) - [TiltrotorExtraControls](msg_docs/TiltrotorExtraControls.md) - [TimesyncStatus](msg_docs/TimesyncStatus.md) + - [TrajectorySetpoint6dof](msg_docs/TrajectorySetpoint6dof.md) - [TransponderReport](msg_docs/TransponderReport.md) - [TuneControl](msg_docs/TuneControl.md) - [UavcanParameterRequest](msg_docs/UavcanParameterRequest.md) @@ -713,6 +718,8 @@ - [WheelEncoders](msg_docs/WheelEncoders.md) - [Wind](msg_docs/Wind.md) - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) + - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) + - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](middleware/mavlink.md) - [Adding Messages](mavlink/adding_messages.md) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index bb538fd661..191aeceafb 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -17304,14 +17304,6 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | 0.2 | 1.0 | 0.05 | 0.4 | s -### FW_SPOILERS_LND (`FLOAT`) {#FW_SPOILERS_LND} - -Spoiler landing setting. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.01 | 0. | norm - ### FW_WR_FF (`FLOAT`) {#FW_WR_FF} Wheel steering rate feed forward. @@ -17378,6 +17370,16 @@ Reboot | minValue | maxValue | increment | default | unit ## FW Auto Landing +### FW_FLAPS_LND_SCL (`FLOAT`) {#FW_FLAPS_LND_SCL} + +Flaps setting during landing. + +Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 1.0 | 0.01 | 1.0 | norm + ### FW_LND_ABORT (`INT32`) {#FW_LND_ABORT} Bit mask to set the automatic landing abort conditions. @@ -17536,29 +17538,25 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | 0 | 2 | | 1 | -## FW Geometry +### FW_SPOILERS_LND (`FLOAT`) {#FW_SPOILERS_LND} -### FW_WING_HEIGHT (`FLOAT`) {#FW_WING_HEIGHT} - -Height (AGL) of the wings when the aircraft is on the ground. - -This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m) +Spoiler landing setting. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.0 | | 1 | 0.5 | m +  | 0.0 | 1.0 | 0.01 | 0. | norm -### FW_WING_SPAN (`FLOAT`) {#FW_WING_SPAN} +## FW Auto Takeoff -The aircraft's wing span (length from tip to tip). +### FW_FLAPS_TO_SCL (`FLOAT`) {#FW_FLAPS_TO_SCL} -This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span) +Flaps setting during take-off. + +Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 0.1 | | 0.1 | 3.0 | m - -## FW Launch detection +  | 0.0 | 1.0 | 0.01 | 0.0 | norm ### FW_LAUN_AC_T (`FLOAT`) {#FW_LAUN_AC_T} @@ -17600,6 +17598,374 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | 0.0 | 10.0 | 0.5 | 0.0 | s +### FW_TKO_AIRSPD (`FLOAT`) {#FW_TKO_AIRSPD} + +Takeoff Airspeed. + +The calibrated airspeed setpoint during the takeoff climbout. If set <= 0, FW_AIRSPD_MIN will be set by default. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | -1.0 | | 0.1 | -1.0 | m/s + +### FW_TKO_PITCH_MIN (`FLOAT`) {#FW_TKO_PITCH_MIN} + +Minimum pitch during takeoff. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | -5.0 | 30.0 | 0.5 | 10.0 | deg + +## FW General + +### FW_GPSF_LT (`INT32`) {#FW_GPSF_LT} + +GPS failure loiter time. + +The time the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0 | 3600 | | 30 | s + +### FW_GPSF_R (`FLOAT`) {#FW_GPSF_R} + +GPS failure fixed roll angle. + +Roll angle in GPS failure loiter mode. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 30.0 | 0.5 | 15.0 | deg + +### FW_POS_STK_CONF (`INT32`) {#FW_POS_STK_CONF} + +Custom stick configuration. + +Applies in manual Position and Altitude flight modes. + +**Bitmask:** + +- `0`: Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick) +- `1`: Enable airspeed setpoint via sticks in altitude and position flight mode + + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0 | 3 | | 2 | + +### FW_P_LIM_MAX (`FLOAT`) {#FW_P_LIM_MAX} + +Maximum pitch angle setpoint. + +Applies in any altitude controlled flight mode. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 60.0 | 0.5 | 30.0 | deg + +### FW_P_LIM_MIN (`FLOAT`) {#FW_P_LIM_MIN} + +Minimum pitch angle setpoint. + +Applies in any altitude controlled flight mode. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | -60.0 | 0.0 | 0.5 | -30.0 | deg + +### FW_R_LIM (`FLOAT`) {#FW_R_LIM} + +Maximum roll angle setpoint. + +Applies in any altitude controlled flight mode. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 35.0 | 65.0 | 0.5 | 50.0 | deg + +### FW_THR_IDLE (`FLOAT`) {#FW_THR_IDLE} + +Idle throttle. + +This is the minimum throttle while on the ground ("landed") in auto modes. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 0.4 | 0.01 | 0.0 | norm + +### FW_THR_MAX (`FLOAT`) {#FW_THR_MAX} + +Throttle limit max. + +Applies in any altitude controlled flight mode. Should be set accordingly to achieve FW_T_CLMB_MAX. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 1.0 | 0.01 | 1.0 | norm + +### FW_THR_MIN (`FLOAT`) {#FW_THR_MIN} + +Throttle limit min. + +Applies in any altitude controlled flight mode. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 1.0 | 0.01 | 0.0 | norm + +### FW_T_CLMB_R_SP (`FLOAT`) {#FW_T_CLMB_R_SP} + +Default target climbrate. + +In auto modes: default climb rate output by controller to achieve altitude setpoints. In manual modes: maximum climb rate setpoint. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.5 | 15 | 0.01 | 3.0 | m/s + +### FW_T_SINK_R_SP (`FLOAT`) {#FW_T_SINK_R_SP} + +Default target sinkrate. + +In auto modes: default sink rate output by controller to achieve altitude setpoints. In manual modes: maximum sink rate setpoint. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.5 | 15 | 0.01 | 2.0 | m/s + +### FW_T_SPDWEIGHT (`FLOAT`) {#FW_T_SPDWEIGHT} + +Speed <--> Altitude weight. + +Adjusts the amount of weighting that the pitch control applies to speed vs height errors. 0 -> control height only 2 -> control speed only (gliders) + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 2.0 | 1.0 | 1.0 | + +### FW_WING_HEIGHT (`FLOAT`) {#FW_WING_HEIGHT} + +Height (AGL) of the wings when the aircraft is on the ground. + +This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m) + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | | 1 | 0.5 | m + +### FW_WING_SPAN (`FLOAT`) {#FW_WING_SPAN} + +The aircraft's wing span (length from tip to tip). + +This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span) + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.1 | | 0.1 | 3.0 | m + +## FW Lateral Control + +### FW_PN_R_SLEW_MAX (`FLOAT`) {#FW_PN_R_SLEW_MAX} + +Path navigation roll slew rate limit. + +Maximum change in roll angle setpoint per second. Applied in all Auto modes, plus manual Position & Altitude modes. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0 | | 1 | 90.0 | deg/s + +## FW Longitudinal Control + +### FW_GND_SPD_MIN (`FLOAT`) {#FW_GND_SPD_MIN} + +Minimum groundspeed. + +The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 40 | 0.5 | 5.0 | m/s + +### FW_THR_SLEW_MAX (`FLOAT`) {#FW_THR_SLEW_MAX} + +Throttle max slew rate. + +Maximum slew rate for the commanded throttle + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 1.0 | 0.01 | 0.0 | + +### FW_T_ALT_TC (`FLOAT`) {#FW_T_ALT_TC} + +Altitude error time constant. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 2.0 | | 0.5 | 5.0 | + +### FW_T_F_ALT_ERR (`FLOAT`) {#FW_T_F_ALT_ERR} + +Fast descend: minimum altitude error. + +Minimum altitude error needed to descend with max airspeed and minimal throttle. A negative value disables fast descend. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | -1.0 | | | -1.0 | + +### FW_T_HRATE_FF (`FLOAT`) {#FW_T_HRATE_FF} + +Height rate feed forward. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 1.0 | 0.05 | 0.3 | + +### FW_T_I_GAIN_PIT (`FLOAT`) {#FW_T_I_GAIN_PIT} + +Integrator gain pitch. + +Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 2.0 | 0.05 | 0.1 | + +### FW_T_PTCH_DAMP (`FLOAT`) {#FW_T_PTCH_DAMP} + +Pitch damping gain. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 2.0 | 0.1 | 0.1 | + +### FW_T_RLL2THR (`FLOAT`) {#FW_T_RLL2THR} + +Roll -> Throttle feedforward. + +Is used to compensate for the additional drag created by turning. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 20.0 | 0.5 | 15.0 | + +### FW_T_SEB_R_FF (`FLOAT`) {#FW_T_SEB_R_FF} + +Specific total energy balance rate feedforward gain. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.5 | 3 | 0.01 | 1.0 | + +### FW_T_SINK_MAX (`FLOAT`) {#FW_T_SINK_MAX} + +Maximum descent rate. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 1.0 | 15.0 | 0.5 | 5.0 | m/s + +### FW_T_SPD_DEV_STD (`FLOAT`) {#FW_T_SPD_DEV_STD} + +Airspeed rate measurement standard deviation. + +For the airspeed filter in TECS. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.01 | 10.0 | 0.1 | 0.2 | m/s^2 + +### FW_T_SPD_PRC_STD (`FLOAT`) {#FW_T_SPD_PRC_STD} + +Process noise standard deviation for the airspeed rate. + +This is defining the noise in the airspeed rate for the constant airspeed rate model of the TECS airspeed filter. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.01 | 10.0 | 0.1 | 0.2 | m/s^2 + +### FW_T_SPD_STD (`FLOAT`) {#FW_T_SPD_STD} + +Airspeed measurement standard deviation. + +For the airspeed filter in TECS. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.01 | 10.0 | 0.1 | 0.07 | m/s + +### FW_T_STE_R_TC (`FLOAT`) {#FW_T_STE_R_TC} + +Specific total energy rate first order filter time constant. + +This filter is applied to the specific total energy rate used for throttle damping. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 2 | 0.01 | 0.4 | + +### FW_T_TAS_TC (`FLOAT`) {#FW_T_TAS_TC} + +True airspeed error time constant. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 2.0 | | 0.5 | 5.0 | + +### FW_T_THR_DAMPING (`FLOAT`) {#FW_T_THR_DAMPING} + +Throttle damping factor. + +This is the damping gain for the throttle demand loop. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 1.0 | 0.01 | 0.05 | + +### FW_T_THR_INTEG (`FLOAT`) {#FW_T_THR_INTEG} + +Integrator gain throttle. + +Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.0 | 1.0 | 0.005 | 0.02 | + +### FW_T_THR_LOW_HGT (`FLOAT`) {#FW_T_THR_LOW_HGT} + +Low-height threshold for tighter altitude tracking. + +Height above ground threshold below which tighter altitude tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC to FW_LND_THRTC_SC*FW_T_ALT_TC. -1 to disable. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | -1 | | 1 | -1. | m + +### FW_T_VERT_ACC (`FLOAT`) {#FW_T_VERT_ACC} + +Maximum vertical acceleration. + +This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 1.0 | 10.0 | 0.5 | 7.0 | m/s^2 + +### FW_WIND_ARSP_SC (`FLOAT`) {#FW_WIND_ARSP_SC} + +Wind-based airspeed scaling factor. + +Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0 | | 0.01 | 0. | + ## FW NPFG Control ### NPFG_DAMPING (`FLOAT`) {#NPFG_DAMPING} @@ -17612,24 +17978,6 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | 0.10 | 1.00 | 0.01 | 0.7 | -### NPFG_EN_MIN_GSP (`INT32`) {#NPFG_EN_MIN_GSP} - -Enable minimum forward ground speed maintaining excess wind handling logic. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | | | | Enabled (1) | - -### NPFG_GSP_MAX_TK (`FLOAT`) {#NPFG_GSP_MAX_TK} - -Maximum, minimum forward ground speed for track keeping in excess wind. - -The maximum value of the minimum forward ground speed that may be commanded by the track keeping excess wind handling logic. Commanded in full at the normalized track error fraction of the track error boundary and reduced to zero on track. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 10.0 | 0.5 | 5.0 | m/s - ### NPFG_LB_PERIOD (`INT32`) {#NPFG_LB_PERIOD} Enable automatic lower bound on the NPFG period. @@ -17680,14 +18028,6 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | 0.1 | 1.0 | 0.01 | 0.32 | -### NPFG_TRACK_KEEP (`INT32`) {#NPFG_TRACK_KEEP} - -Enable track keeping excess wind handling logic. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | | | | Enabled (1) | - ### NPFG_UB_PERIOD (`INT32`) {#NPFG_UB_PERIOD} Enable automatic upper bound on the NPFG period. @@ -17698,64 +18038,18 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | | | | Enabled (1) | -### NPFG_WIND_REG (`INT32`) {#NPFG_WIND_REG} - -Enable wind excess regulation. - -Disabling this parameter further disables all other airspeed incrementation options. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | | | | Enabled (1) | - -## FW Path Control - -### FW_PN_R_SLEW_MAX (`FLOAT`) {#FW_PN_R_SLEW_MAX} - -Path navigation roll slew rate limit. - -Maximum change in roll angle setpoint per second. Applied in all Auto modes, plus manual Position & Altitude modes. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0 | | 1 | 90.0 | deg/s - -### FW_POS_STK_CONF (`INT32`) {#FW_POS_STK_CONF} - -Custom stick configuration. - -Applies in manual Position and Altitude flight modes. - -**Bitmask:** - -- `0`: Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick) -- `1`: Enable airspeed setpoint via sticks in altitude and position flight mode - - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0 | 3 | | 2 | - -### FW_R_LIM (`FLOAT`) {#FW_R_LIM} - -Maximum roll angle setpoint. - -Applies in any altitude controlled flight mode. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 35.0 | 65.0 | 0.5 | 50.0 | deg - -### FW_TKO_PITCH_MIN (`FLOAT`) {#FW_TKO_PITCH_MIN} - -Minimum pitch during takeoff. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | -5.0 | 30.0 | 0.5 | 10.0 | deg - ## FW Performance +### FW_AIRSPD_FLP_SC (`FLOAT`) {#FW_AIRSPD_FLP_SC} + +Airspeed scale with full flaps. + +Factor applied to the minimum and stall airspeed when flaps are fully deployed. + +Reboot | minValue | maxValue | increment | default | unit +--- | --- | --- | --- | --- | --- +  | 0.5 | 1 | 0.01 | 1. | + ### FW_AIRSPD_MAX (`FLOAT`) {#FW_AIRSPD_MAX} Maximum Airspeed (CAS). @@ -17992,26 +18286,6 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | -0.5 | 0.5 | 0.01 | 0.0 | -### FW_FLAPS_LND_SCL (`FLOAT`) {#FW_FLAPS_LND_SCL} - -Flaps setting during landing. - -Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.01 | 1.0 | norm - -### FW_FLAPS_TO_SCL (`FLOAT`) {#FW_FLAPS_TO_SCL} - -Flaps setting during take-off. - -Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.01 | 0.0 | norm - ### FW_MAN_P_SC (`FLOAT`) {#FW_MAN_P_SC} Manual pitch scale. @@ -18207,286 +18481,6 @@ Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | 0.0 | 10 | 0.005 | 0.05 | %/rad/s -## FW TECS - -### FW_GND_SPD_MIN (`FLOAT`) {#FW_GND_SPD_MIN} - -Minimum groundspeed. - -The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 40 | 0.5 | 5.0 | m/s - -### FW_P_LIM_MAX (`FLOAT`) {#FW_P_LIM_MAX} - -Maximum pitch angle setpoint. - -Applies in any altitude controlled flight mode. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 60.0 | 0.5 | 30.0 | deg - -### FW_P_LIM_MIN (`FLOAT`) {#FW_P_LIM_MIN} - -Minimum pitch angle setpoint. - -Applies in any altitude controlled flight mode. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | -60.0 | 0.0 | 0.5 | -30.0 | deg - -### FW_THR_IDLE (`FLOAT`) {#FW_THR_IDLE} - -Idle throttle. - -This is the minimum throttle while on the ground ("landed") in auto modes. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 0.4 | 0.01 | 0.0 | norm - -### FW_THR_MAX (`FLOAT`) {#FW_THR_MAX} - -Throttle limit max. - -Applies in any altitude controlled flight mode. Should be set accordingly to achieve FW_T_CLMB_MAX. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.01 | 1.0 | norm - -### FW_THR_MIN (`FLOAT`) {#FW_THR_MIN} - -Throttle limit min. - -Applies in any altitude controlled flight mode. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.01 | 0.0 | norm - -### FW_THR_SLEW_MAX (`FLOAT`) {#FW_THR_SLEW_MAX} - -Throttle max slew rate. - -Maximum slew rate for the commanded throttle - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.01 | 0.0 | - -### FW_TKO_AIRSPD (`FLOAT`) {#FW_TKO_AIRSPD} - -Takeoff Airspeed. - -The calibrated airspeed setpoint during the takeoff climbout. If set <= 0, FW_AIRSPD_MIN will be set by default. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | -1.0 | | 0.1 | -1.0 | m/s - -### FW_T_ALT_TC (`FLOAT`) {#FW_T_ALT_TC} - -Altitude error time constant. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 2.0 | | 0.5 | 5.0 | - -### FW_T_CLMB_R_SP (`FLOAT`) {#FW_T_CLMB_R_SP} - -Default target climbrate. - -In auto modes: default climb rate output by controller to achieve altitude setpoints. In manual modes: maximum climb rate setpoint. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.5 | 15 | 0.01 | 3.0 | m/s - -### FW_T_F_ALT_ERR (`FLOAT`) {#FW_T_F_ALT_ERR} - -Fast descend: minimum altitude error. - -Minimum altitude error needed to descend with max airspeed and minimal throttle. A negative value disables fast descend. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | -1.0 | | | -1.0 | - -### FW_T_HRATE_FF (`FLOAT`) {#FW_T_HRATE_FF} - -Height rate feed forward. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.05 | 0.3 | - -### FW_T_I_GAIN_PIT (`FLOAT`) {#FW_T_I_GAIN_PIT} - -Integrator gain pitch. - -Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 2.0 | 0.05 | 0.1 | - -### FW_T_PTCH_DAMP (`FLOAT`) {#FW_T_PTCH_DAMP} - -Pitch damping gain. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 2.0 | 0.1 | 0.1 | - -### FW_T_RLL2THR (`FLOAT`) {#FW_T_RLL2THR} - -Roll -> Throttle feedforward. - -Is used to compensate for the additional drag created by turning. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 20.0 | 0.5 | 15.0 | - -### FW_T_SEB_R_FF (`FLOAT`) {#FW_T_SEB_R_FF} - -Specific total energy balance rate feedforward gain. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.5 | 3 | 0.01 | 1.0 | - -### FW_T_SINK_MAX (`FLOAT`) {#FW_T_SINK_MAX} - -Maximum descent rate. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 1.0 | 15.0 | 0.5 | 5.0 | m/s - -### FW_T_SINK_R_SP (`FLOAT`) {#FW_T_SINK_R_SP} - -Default target sinkrate. - -In auto modes: default sink rate output by controller to achieve altitude setpoints. In manual modes: maximum sink rate setpoint. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.5 | 15 | 0.01 | 2.0 | m/s - -### FW_T_SPDWEIGHT (`FLOAT`) {#FW_T_SPDWEIGHT} - -Speed <--> Altitude weight. - -Adjusts the amount of weighting that the pitch control applies to speed vs height errors. 0 -> control height only 2 -> control speed only (gliders) - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 2.0 | 1.0 | 1.0 | - -### FW_T_SPD_DEV_STD (`FLOAT`) {#FW_T_SPD_DEV_STD} - -Airspeed rate measurement standard deviation. - -For the airspeed filter in TECS. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.01 | 10.0 | 0.1 | 0.2 | m/s^2 - -### FW_T_SPD_PRC_STD (`FLOAT`) {#FW_T_SPD_PRC_STD} - -Process noise standard deviation for the airspeed rate. - -This is defining the noise in the airspeed rate for the constant airspeed rate model of the TECS airspeed filter. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.01 | 10.0 | 0.1 | 0.2 | m/s^2 - -### FW_T_SPD_STD (`FLOAT`) {#FW_T_SPD_STD} - -Airspeed measurement standard deviation. - -For the airspeed filter in TECS. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.01 | 10.0 | 0.1 | 0.07 | m/s - -### FW_T_STE_R_TC (`FLOAT`) {#FW_T_STE_R_TC} - -Specific total energy rate first order filter time constant. - -This filter is applied to the specific total energy rate used for throttle damping. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 2 | 0.01 | 0.4 | - -### FW_T_TAS_TC (`FLOAT`) {#FW_T_TAS_TC} - -True airspeed error time constant. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 2.0 | | 0.5 | 5.0 | - -### FW_T_THR_DAMPING (`FLOAT`) {#FW_T_THR_DAMPING} - -Throttle damping factor. - -This is the damping gain for the throttle demand loop. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.01 | 0.05 | - -### FW_T_THR_INTEG (`FLOAT`) {#FW_T_THR_INTEG} - -Integrator gain throttle. - -Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 1.0 | 0.005 | 0.02 | - -### FW_T_THR_LOW_HGT (`FLOAT`) {#FW_T_THR_LOW_HGT} - -Low-height threshold for tighter altitude tracking. - -Height above ground threshold below which tighter altitude tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC to FW_LND_THRTC_SC*FW_T_ALT_TC. -1 to disable. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | -1 | | 1 | -1. | m - -### FW_T_VERT_ACC (`FLOAT`) {#FW_T_VERT_ACC} - -Maximum vertical acceleration. - -This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 1.0 | 10.0 | 0.5 | 7.0 | m/s^2 - -### FW_WIND_ARSP_SC (`FLOAT`) {#FW_WIND_ARSP_SC} - -Wind-based airspeed scaling factor. - -Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0 | | 0.01 | 0. | - ## Failure Detector ### FD_ACT_EN (`INT32`) {#FD_ACT_EN} @@ -23288,26 +23282,6 @@ Reboot | minValue | maxValue | increment | default | unit ## Mission -### FW_GPSF_LT (`INT32`) {#FW_GPSF_LT} - -GPS failure loiter time. - -The time the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0 | 3600 | | 30 | s - -### FW_GPSF_R (`FLOAT`) {#FW_GPSF_R} - -GPS failure fixed roll angle. - -Roll angle in GPS failure loiter mode. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0.0 | 30.0 | 0.5 | 15.0 | deg - ### MIS_COMMAND_TOUT (`FLOAT`) {#MIS_COMMAND_TOUT} Timeout to allow the payload to execute the mission command. @@ -23957,7 +23931,7 @@ Limits the acceleration of the yaw setpoint to avoid large control output and mi Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 5 | 360 | 5 | 60. | deg/s^2 +  | 5 | 360 | 5 | 20. | deg/s^2 ### MPC_YAWRAUTO_MAX (`FLOAT`) {#MPC_YAWRAUTO_MAX} @@ -23967,7 +23941,7 @@ Limits the rate of change of the yaw setpoint to avoid large control output and Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -  | 5 | 360 | 5 | 45. | deg/s +  | 5 | 360 | 5 | 60. | deg/s ## Multicopter Position Control @@ -28072,38 +28046,14 @@ Reboot | minValue | maxValue | increment | default | unit ## Runway Takeoff -### RWTO_HDG (`INT32`) {#RWTO_HDG} - -Specifies which heading should be held during the runway takeoff ground roll. - -0: airframe heading when takeoff is initiated 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF position defined by operator) - -**Values:** - -- `0`: Airframe -- `1`: Runway - - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 0 | 1 | | 0 | - ### RWTO_MAX_THR (`FLOAT`) {#RWTO_MAX_THR} -Max throttle during runway takeoff. +Throttle during runway takeoff. Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | ---   | 0.0 | 1.0 | 0.01 | 1.0 | norm -### RWTO_NPFG_PERIOD (`FLOAT`) {#RWTO_NPFG_PERIOD} - -NPFG period while steering on runway. - -Reboot | minValue | maxValue | increment | default | unit ---- | --- | --- | --- | --- | --- -  | 1.0 | 100.0 | 0.1 | 5.0 | s - ### RWTO_NUDGE (`INT32`) {#RWTO_NUDGE} Enable use of yaw stick for nudging the wheel during runway ground roll. @@ -28274,11 +28224,12 @@ This integer bitmask controls the set and rates of logged topics. The default al - `8`: Raw FIFO high-rate IMU (Gyro) - `9`: Raw FIFO high-rate IMU (Accel) - `10`: Mavlink tunnel message logging +- `11`: High rate sensors Reboot | minValue | maxValue | increment | default | unit --- | --- | --- | --- | --- | --- -✓ | 0 | 2047 | | 1 | +✓ | 0 | 4095 | | 1 | ### SDLOG_UTC_OFFSET (`INT32`) {#SDLOG_UTC_OFFSET} diff --git a/docs/en/frames_plane/reptile_dragon_2.md b/docs/en/frames_plane/reptile_dragon_2.md index 0aaa509958..ceed4a5854 100644 --- a/docs/en/frames_plane/reptile_dragon_2.md +++ b/docs/en/frames_plane/reptile_dragon_2.md @@ -314,7 +314,7 @@ Access to this cable can be accomplished by simply removing the rear hatch and u ## Firmware Build -You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. +You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver_radio_control.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. These require some custom configuration to enable. diff --git a/docs/en/modules/modules_controller.md b/docs/en/modules/modules_controller.md index e09206b296..049a5659df 100644 --- a/docs/en/modules/modules_controller.md +++ b/docs/en/modules/modules_controller.md @@ -95,19 +95,19 @@ fw_att_control [arguments...] status print status info ``` -## fw_pos_control +## fw_lat_lon_control -Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_pos_control) +Source: [modules/fw_lateral_longitudinal_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_lateral_longitudinal_control) ### Description -fw_pos_control is the fixed-wing position controller. +fw_lat_lon_control computes attitude and throttle setpoints from lateral and longitudinal control setpoints. -### Usage {#fw_pos_control_usage} +### Usage {#fw_lat_lon_control_usage} ``` -fw_pos_control [arguments...] +fw_lat_lon_control [arguments...] Commands: start [vtol] VTOL mode @@ -117,6 +117,29 @@ fw_pos_control [arguments...] status print status info ``` +## fw_mode_manager + +Source: [modules/fw_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_mode_manager) + + +### Description +This implements the setpoint generation for all PX4-internal fixed-wing modes, height-rate control and higher. +It takes the current mode state of the vehicle as input and outputs setpoints consumed by the fixed-wing +lateral-longitudinal controller and and controllers below that (attitude, rate). + + +### Usage {#fw_mode_manager_usage} + +``` +fw_mode_manager [arguments...] + Commands: + start + + stop + + status print status info +``` + ## fw_rate_control Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_rate_control) diff --git a/docs/en/modules/modules_driver.md b/docs/en/modules/modules_driver.md index 3c5f1966ff..1b8d7d6f2f 100644 --- a/docs/en/modules/modules_driver.md +++ b/docs/en/modules/modules_driver.md @@ -290,7 +290,9 @@ dshot [arguments...] start telemetry Enable Telemetry on a UART - UART device + -d UART device + values: + [-x] Swap RX/TX pins reverse Reverse motor direction [-m ] Motor index (1-based, default=all) diff --git a/docs/en/modules/modules_system.md b/docs/en/modules/modules_system.md index 3bd92fa971..051b7137db 100644 --- a/docs/en/modules/modules_system.md +++ b/docs/en/modules/modules_system.md @@ -330,6 +330,7 @@ i2c_launcher [arguments...] Commands: start -b Bus number + -t battery index for calibration values (1 or 3) stop diff --git a/docs/en/msg_docs/AirspeedValidated.md b/docs/en/msg_docs/AirspeedValidated.md index 78c57ce748..b5fe9191a5 100644 --- a/docs/en/msg_docs/AirspeedValidated.md +++ b/docs/en/msg_docs/AirspeedValidated.md @@ -2,22 +2,28 @@ -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AirspeedValidated.msg) +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +uint32 MESSAGE_VERSION = 1 + uint64 timestamp # time since system start (microseconds) -float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid -float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid +float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +int8 airspeed_source # Source of currently published airspeed values +int8 DISABLED = -1 +int8 GROUND_MINUS_WIND = 0 +int8 SENSOR_1 = 1 +int8 SENSOR_2 = 2 +int8 SENSOR_3 = 3 +int8 SYNTHETIC = 4 + +# debug states float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid - -bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. - -int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid - +float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] float32 throttle_filtered # filtered fixed-wing throttle [-] float32 pitch_filtered # filtered pitch [rad] diff --git a/docs/en/msg_docs/AirspeedValidatedV0.md b/docs/en/msg_docs/AirspeedValidatedV0.md new file mode 100644 index 0000000000..9cd392a955 --- /dev/null +++ b/docs/en/msg_docs/AirspeedValidatedV0.md @@ -0,0 +1,27 @@ +# AirspeedValidatedV0 (UORB message) + + + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/AirspeedValidatedV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid +float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid + +float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid +float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid + +bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. + +int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid + +float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] +float32 throttle_filtered # filtered fixed-wing throttle [-] +float32 pitch_filtered # filtered pitch [rad] + +``` diff --git a/docs/en/msg_docs/Buffer128.md b/docs/en/msg_docs/Buffer128.md deleted file mode 100644 index 2df2cf3673..0000000000 --- a/docs/en/msg_docs/Buffer128.md +++ /dev/null @@ -1,17 +0,0 @@ -# Buffer128 (UORB message) - - - -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Buffer128.msg) - -```c -uint64 timestamp # time since system start (microseconds) - -uint8 len # length of data -uint32 MAX_BUFLEN = 128 - -uint8[128] data # data - -# TOPICS voxl2_io_data - -``` diff --git a/docs/en/msg_docs/CellularStatus.md b/docs/en/msg_docs/CellularStatus.md index 87fda0b991..466a1272fe 100644 --- a/docs/en/msg_docs/CellularStatus.md +++ b/docs/en/msg_docs/CellularStatus.md @@ -1,37 +1,49 @@ # CellularStatus (UORB message) +Cellular status +This is currently used only for logging cell status from MAVLink. [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CellularStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Cellular status +# +# This is currently used only for logging cell status from MAVLink. -uint8 CELLULAR_STATUS_FLAG_UNKNOWN=0 # State unknown or not reportable -uint8 CELLULAR_STATUS_FLAG_FAILED=1 # velocity setpoint -uint8 CELLULAR_STATUS_FLAG_INITIALIZING=2 # Modem is being initialized -uint8 CELLULAR_STATUS_FLAG_LOCKED=3 # Modem is locked -uint8 CELLULAR_STATUS_FLAG_DISABLED=4 # Modem is not enabled and is powered down -uint8 CELLULAR_STATUS_FLAG_DISABLING=5 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLING=6 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLED=7 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint8 CELLULAR_STATUS_FLAG_SEARCHING=8 # Modem is searching for a network provider to register -uint8 CELLULAR_STATUS_FLAG_REGISTERED=9 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint8 CELLULAR_STATUS_FLAG_DISCONNECTING=10 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint8 CELLULAR_STATUS_FLAG_CONNECTING=11 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint8 CELLULAR_STATUS_FLAG_CONNECTED=12 # One or more packet data bearers is active and connected +uint64 timestamp # [us] Time since system start. -uint8 CELLULAR_NETWORK_FAILED_REASON_NONE=0 # No error -uint8 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN=1 # Error state is unknown -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING=2 # SIM is required for the modem but missing -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3 # SIM is available, but not usable for connection +uint16 status # [@enum STATUS_FLAG] Status bitmap. +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable. +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable. +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized. +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked. +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down. +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state. +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state. +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections. +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register. +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use. +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated. +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered. +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected. -uint16 status # Status bitmap 1: Roaming is active -uint8 failure_reason #Failure reason when status in in CELLUAR_STATUS_FAILED -uint8 type # Cellular network radio type 0: none 1: gsm 2: cdma 3: wcdma 4: lte -uint8 quality # Cellular network RSSI/RSRP in dBm, absolute value -uint16 mcc # Mobile country code. If unknown, set to: UINT16_MAX -uint16 mnc # Mobile network code. If unknown, set to: UINT16_MAX -uint16 lac # Location area code. If unknown, set to: 0 +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason. +uint8 FAILURE_REASON_NONE = 0 # No error. +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown. +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing. +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection. + +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type. +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE + +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value. +uint16 mcc # [@invalid UINT16_MAX] Mobile country code. +uint16 mnc # [@invalid UINT16_MAX] Mobile network code. +uint16 lac # [@invalid 0] Location area code. ``` diff --git a/docs/en/msg_docs/FixedWingLateralGuidanceStatus.md b/docs/en/msg_docs/FixedWingLateralGuidanceStatus.md new file mode 100644 index 0000000000..02dc50b410 --- /dev/null +++ b/docs/en/msg_docs/FixedWingLateralGuidanceStatus.md @@ -0,0 +1,23 @@ +# FixedWingLateralGuidanceStatus (UORB message) + +Fixed Wing Lateral Guidance Status message +Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralGuidanceStatus.msg) + +```c +# Fixed Wing Lateral Guidance Status message +# Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +uint64 timestamp # time since system start (microseconds) + +float32 course_setpoint # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. Set by guidance law +float32 lateral_acceleration_ff # [m/s^2] [FRD] lateral acceleration demand only for maintaining curvature +float32 bearing_feas # [@range 0,1] bearing feasibility +float32 bearing_feas_on_track # [@range 0,1] on-track bearing feasibility +float32 signed_track_error # [m] signed track error +float32 track_error_bound # [m] track error bound +float32 adapted_period # [s] adapted period (if auto-tuning enabled) +uint8 wind_est_valid # [boolean] true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) + +``` diff --git a/docs/en/msg_docs/FixedWingLateralSetpoint.md b/docs/en/msg_docs/FixedWingLateralSetpoint.md new file mode 100644 index 0000000000..153167bb62 --- /dev/null +++ b/docs/en/msg_docs/FixedWingLateralSetpoint.md @@ -0,0 +1,22 @@ +# FixedWingLateralSetpoint (UORB message) + +Fixed Wing Lateral Setpoint message +Used by the fw_lateral_longitudinal_control module +At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLateralSetpoint.msg) + +```c +# Fixed Wing Lateral Setpoint message +# Used by the fw_lateral_longitudinal_control module +# At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. +float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. +float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. + +``` diff --git a/docs/en/msg_docs/FixedWingLateralStatus.md b/docs/en/msg_docs/FixedWingLateralStatus.md new file mode 100644 index 0000000000..9214d1e9e0 --- /dev/null +++ b/docs/en/msg_docs/FixedWingLateralStatus.md @@ -0,0 +1,17 @@ +# FixedWingLateralStatus (UORB message) + +Fixed Wing Lateral Status message +Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralStatus.msg) + +```c +# Fixed Wing Lateral Status message +# Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_acceleration_setpoint # [m/s^2] [FRD] resultant lateral acceleration setpoint +float32 can_run_factor # [norm] [@range 0, 1] estimate of certainty of the correct functionality of the npfg roll setpoint + +``` diff --git a/docs/en/msg_docs/FixedWingLongitudinalSetpoint.md b/docs/en/msg_docs/FixedWingLongitudinalSetpoint.md new file mode 100644 index 0000000000..6b8fb29e5b --- /dev/null +++ b/docs/en/msg_docs/FixedWingLongitudinalSetpoint.md @@ -0,0 +1,26 @@ +# FixedWingLongitudinalSetpoint (UORB message) + +Fixed Wing Longitudinal Setpoint message +Used by the fw_lateral_longitudinal_control module +If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +If both altitude and height_rate are NAN, the controller maintains the current altitude. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLongitudinalSetpoint.msg) + +```c +# Fixed Wing Longitudinal Setpoint message +# Used by the fw_lateral_longitudinal_control module +# If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +# If both altitude and height_rate are NAN, the controller maintains the current altitude. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite +float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not controlled directly +float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used +float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller +float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller + +``` diff --git a/docs/en/msg_docs/FixedWingRunwayControl.md b/docs/en/msg_docs/FixedWingRunwayControl.md new file mode 100644 index 0000000000..9e9f5ff428 --- /dev/null +++ b/docs/en/msg_docs/FixedWingRunwayControl.md @@ -0,0 +1,19 @@ +# FixedWingRunwayControl (UORB message) + +Auxiliary control fields for fixed-wing runway takeoff/landing + +Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingRunwayControl.msg) + +```c +# Auxiliary control fields for fixed-wing runway takeoff/landing + +# Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +uint64 timestamp # [us] time since system start + +bool wheel_steering_enabled # Flag that enables the wheel steering. +float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. + +``` diff --git a/docs/en/msg_docs/LateralControlConfiguration.md b/docs/en/msg_docs/LateralControlConfiguration.md new file mode 100644 index 0000000000..b0a03a6378 --- /dev/null +++ b/docs/en/msg_docs/LateralControlConfiguration.md @@ -0,0 +1,18 @@ +# LateralControlConfiguration (UORB message) + +Fixed Wing Lateral Control Configuration message +Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LateralControlConfiguration.msg) + +```c +# Fixed Wing Lateral Control Configuration message +# Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY + +``` diff --git a/docs/en/msg_docs/LongitudinalControlConfiguration.md b/docs/en/msg_docs/LongitudinalControlConfiguration.md new file mode 100644 index 0000000000..901d5c23bc --- /dev/null +++ b/docs/en/msg_docs/LongitudinalControlConfiguration.md @@ -0,0 +1,28 @@ +# LongitudinalControlConfiguration (UORB message) + +Fixed Wing Longitudinal Control Configuration message +Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +and configure the resultant setpoints. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LongitudinalControlConfiguration.msg) + +```c +# Fixed Wing Longitudinal Control Configuration message +# Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +# and configure the resultant setpoints. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 pitch_min # [rad][@range -pi, pi] defaults to FW_P_LIM_MIN if NAN. +float32 pitch_max # [rad][@range -pi, pi] defaults to FW_P_LIM_MAX if NAN. +float32 throttle_min # [norm] [@range 0,1] deaults to FW_THR_MIN if NAN. +float32 throttle_max # [norm] [@range 0,1] defaults to FW_THR_MAX if NAN. +float32 climb_rate_target # [m/s] target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only +bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking +bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller + +``` diff --git a/docs/en/msg_docs/NpfgStatus.md b/docs/en/msg_docs/NpfgStatus.md deleted file mode 100644 index 281c27acab..0000000000 --- a/docs/en/msg_docs/NpfgStatus.md +++ /dev/null @@ -1,26 +0,0 @@ -# NpfgStatus (UORB message) - - - -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NpfgStatus.msg) - -```c -uint64 timestamp # time since system start (microseconds) - -uint8 wind_est_valid # (boolean) true = wind estimate is valid and/or being used by controller (also indicates if wind est usage is disabled despite being valid) -float32 lat_accel # resultant lateral acceleration reference [m/s^2] -float32 lat_accel_ff # lateral acceleration demand only for maintaining curvature [m/s^2] -float32 bearing_feas # bearing feasibility [0,1] -float32 bearing_feas_on_track # on-track bearing feasibility [0,1] -float32 signed_track_error # signed track error [m] -float32 track_error_bound # track error bound [m] -float32 airspeed_ref # (true) airspeed reference [m/s] -float32 bearing # bearing angle [rad] -float32 heading_ref # heading angle reference [rad] -float32 min_ground_speed_ref # minimum forward ground speed reference [m/s] -float32 adapted_period # adapted period (if auto-tuning enabled) [s] -float32 p_gain # controller proportional gain [rad/s] -float32 time_const # controller time constant [s] -float32 can_run_factor # estimate of certainty of the correct functionality of the npfg roll setpoint in [0, 1] - -``` diff --git a/docs/en/msg_docs/PurePursuitStatus.md b/docs/en/msg_docs/PurePursuitStatus.md index 41f4b9054f..c807b41165 100644 --- a/docs/en/msg_docs/PurePursuitStatus.md +++ b/docs/en/msg_docs/PurePursuitStatus.md @@ -13,6 +13,4 @@ float32 crosstrack_error # [m] Shortest distance from the vehicle to the pat float32 distance_to_waypoint # [m] Distance from the vehicle to the current waypoint float32 bearing_to_waypoint # [rad] Bearing towards current waypoint -# TOPICS pure_pursuit_status - ``` diff --git a/docs/en/msg_docs/RateCtrlStatus.md b/docs/en/msg_docs/RateCtrlStatus.md index 054a8aa9fd..28adaafbbd 100644 --- a/docs/en/msg_docs/RateCtrlStatus.md +++ b/docs/en/msg_docs/RateCtrlStatus.md @@ -11,6 +11,5 @@ uint64 timestamp # time since system start (microseconds) float32 rollspeed_integ float32 pitchspeed_integ float32 yawspeed_integ -float32 wheel_rate_integ # FW only and optional ``` diff --git a/docs/en/msg_docs/RoverAttitudeSetpoint.md b/docs/en/msg_docs/RoverAttitudeSetpoint.md index 922e5d05eb..c7b877c7f5 100644 --- a/docs/en/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/en/msg_docs/RoverAttitudeSetpoint.md @@ -9,6 +9,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_setpoint # [rad] Expressed in NED frame -# TOPICS rover_attitude_setpoint - ``` diff --git a/docs/en/msg_docs/RoverAttitudeStatus.md b/docs/en/msg_docs/RoverAttitudeStatus.md index 5b757b2e5c..3eae8b3f21 100644 --- a/docs/en/msg_docs/RoverAttitudeStatus.md +++ b/docs/en/msg_docs/RoverAttitudeStatus.md @@ -10,6 +10,4 @@ uint64 timestamp # time since system start (microseconds) float32 measured_yaw # [rad/s] Measured yaw rate float32 adjusted_yaw_setpoint # [rad/s] Yaw setpoint that is being tracked (Applied slew rates) -# TOPICS rover_attitude_status - ``` diff --git a/docs/en/msg_docs/RoverMecanumGuidanceStatus.md b/docs/en/msg_docs/RoverMecanumGuidanceStatus.md deleted file mode 100644 index 4a907f45b0..0000000000 --- a/docs/en/msg_docs/RoverMecanumGuidanceStatus.md +++ /dev/null @@ -1,16 +0,0 @@ -# RoverMecanumGuidanceStatus (UORB message) - - - -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverMecanumGuidanceStatus.msg) - -```c -uint64 timestamp # time since system start (microseconds) - -float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller -float32 heading_error # [rad] Heading error of the pure pursuit controller -float32 desired_speed # [m/s] Desired velocity magnitude (speed) - -# TOPICS rover_mecanum_guidance_status - -``` diff --git a/docs/en/msg_docs/RoverMecanumSetpoint.md b/docs/en/msg_docs/RoverMecanumSetpoint.md deleted file mode 100644 index 88a6f75ffe..0000000000 --- a/docs/en/msg_docs/RoverMecanumSetpoint.md +++ /dev/null @@ -1,20 +0,0 @@ -# RoverMecanumSetpoint (UORB message) - - - -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverMecanumSetpoint.msg) - -```c -uint64 timestamp # time since system start (microseconds) - -float32 forward_speed_setpoint # [m/s] Desired forward speed -float32 forward_speed_setpoint_normalized # [-1, 1] Desired normalized forward speed -float32 lateral_speed_setpoint # [m/s] Desired lateral speed -float32 lateral_speed_setpoint_normalized # [-1, 1] Desired normalized lateral speed -float32 yaw_rate_setpoint # [rad/s] Desired yaw rate -float32 speed_diff_setpoint_normalized # [-1, 1] Normalized speed difference between the left and right wheels -float32 yaw_setpoint # [rad] Desired yaw (heading) - -# TOPICS rover_mecanum_setpoint - -``` diff --git a/docs/en/msg_docs/RoverMecanumStatus.md b/docs/en/msg_docs/RoverMecanumStatus.md deleted file mode 100644 index 1330e7b923..0000000000 --- a/docs/en/msg_docs/RoverMecanumStatus.md +++ /dev/null @@ -1,26 +0,0 @@ -# RoverMecanumStatus (UORB message) - - - -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverMecanumStatus.msg) - -```c -uint64 timestamp # time since system start (microseconds) - -float32 measured_forward_speed # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards -float32 adjusted_forward_speed_setpoint # [m/s] Speed setpoint after applying slew rate -float32 measured_lateral_speed # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left -float32 adjusted_lateral_speed_setpoint # [m/s] Speed setpoint after applying slew rate -float32 measured_yaw_rate # [rad/s] Measured yaw rate -float32 clyaw_yaw_rate_setpoint # [rad/s] Yaw rate setpoint output by the closed loop yaw controller -float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint from the closed loop yaw controller -float32 measured_yaw # [rad] Measured yaw -float32 adjusted_yaw_setpoint # [rad] Yaw setpoint after applying slew rate -float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller -float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller -float32 pid_forward_throttle_integral # Integral of the PID for the closed loop forward speed controller -float32 pid_lateral_throttle_integral # Integral of the PID for the closed loop lateral speed controller - -# TOPICS rover_mecanum_status - -``` diff --git a/docs/en/msg_docs/RoverPositionSetpoint.md b/docs/en/msg_docs/RoverPositionSetpoint.md new file mode 100644 index 0000000000..ae9bd9435e --- /dev/null +++ b/docs/en/msg_docs/RoverPositionSetpoint.md @@ -0,0 +1,17 @@ +# RoverPositionSetpoint (UORB message) + + + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32[2] position_ned # 2-dimensional position setpoint in NED frame [m] +float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position) +float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed) +float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero) + +float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw) + +``` diff --git a/docs/en/msg_docs/RoverRateSetpoint.md b/docs/en/msg_docs/RoverRateSetpoint.md index 68ddf65176..80673ec810 100644 --- a/docs/en/msg_docs/RoverRateSetpoint.md +++ b/docs/en/msg_docs/RoverRateSetpoint.md @@ -9,6 +9,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_rate_setpoint # [rad/s] Expressed in NED frame -# TOPICS rover_rate_setpoint - ``` diff --git a/docs/en/msg_docs/RoverRateStatus.md b/docs/en/msg_docs/RoverRateStatus.md index e61ae29562..bf482738b3 100644 --- a/docs/en/msg_docs/RoverRateStatus.md +++ b/docs/en/msg_docs/RoverRateStatus.md @@ -11,6 +11,4 @@ float32 measured_yaw_rate # [rad/s] Measured yaw rate float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint that is being tracked (Applied slew rates) float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller -# TOPICS rover_rate_status - ``` diff --git a/docs/en/msg_docs/RoverSteeringSetpoint.md b/docs/en/msg_docs/RoverSteeringSetpoint.md index 0d74543ee9..fb21dba418 100644 --- a/docs/en/msg_docs/RoverSteeringSetpoint.md +++ b/docs/en/msg_docs/RoverSteeringSetpoint.md @@ -7,9 +7,8 @@ ```c uint64 timestamp # time since system start (microseconds) -float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Only for Ackermann-steered rovers) -float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Only for Differential/Mecanum rovers) +float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Ackermann only, Positiv: Steer right, Negativ: Steer left) -# TOPICS rover_steering_setpoint +float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Differential/Mecanum only, Positiv = Turn right, Negativ: Turn left) ``` diff --git a/docs/en/msg_docs/RoverThrottleSetpoint.md b/docs/en/msg_docs/RoverThrottleSetpoint.md index 6ba6bc1efc..8b4697eb13 100644 --- a/docs/en/msg_docs/RoverThrottleSetpoint.md +++ b/docs/en/msg_docs/RoverThrottleSetpoint.md @@ -8,9 +8,7 @@ uint64 timestamp # time since system start (microseconds) -float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] -float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] - -# TOPICS rover_throttle_setpoint +float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] (Positiv = forwards, Negativ = backwards) +float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] (Mecanum only, Positiv = right, Negativ = left) ``` diff --git a/docs/en/msg_docs/RoverVelocitySetpoint.md b/docs/en/msg_docs/RoverVelocitySetpoint.md new file mode 100644 index 0000000000..aa74dd065d --- /dev/null +++ b/docs/en/msg_docs/RoverVelocitySetpoint.md @@ -0,0 +1,14 @@ +# RoverVelocitySetpoint (UORB message) + + + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocitySetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative) +float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction] +float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame + +``` diff --git a/docs/en/msg_docs/RoverVelocityStatus.md b/docs/en/msg_docs/RoverVelocityStatus.md index adb4480ac3..16a7e27684 100644 --- a/docs/en/msg_docs/RoverVelocityStatus.md +++ b/docs/en/msg_docs/RoverVelocityStatus.md @@ -8,14 +8,10 @@ uint64 timestamp # time since system start (microseconds) float32 measured_speed_body_x # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards -float32 speed_body_x_setpoint # [m/s] Speed setpoint in body x direction. Positiv: forwards, Negativ: backwards float32 adjusted_speed_body_x_setpoint # [m/s] Post slew rate speed setpoint in body x direction. Positiv: forwards, Negativ: backwards -float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left -float32 speed_body_y_setpoint # [m/s] Speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) -float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) float32 pid_throttle_body_x_integral # Integral of the PID for the closed loop controller of the speed in body x direction -float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction - -# TOPICS rover_velocity_status +float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction (Mecanum only) ``` diff --git a/docs/en/msg_docs/TrajectorySetpoint6dof.md b/docs/en/msg_docs/TrajectorySetpoint6dof.md new file mode 100644 index 0000000000..f2629e19c4 --- /dev/null +++ b/docs/en/msg_docs/TrajectorySetpoint6dof.md @@ -0,0 +1,23 @@ +# TrajectorySetpoint6dof (UORB message) + +Trajectory setpoint in NED frame +Input to position controller. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TrajectorySetpoint6dof.msg) + +```c +# Trajectory setpoint in NED frame +# Input to position controller. + +uint64 timestamp # time since system start (microseconds) + +# NED local world frame +float32[3] position # in meters +float32[3] velocity # in meters/second +float32[3] acceleration # in meters/second^2 +float32[3] jerk # in meters/second^3 (for logging only) + +float32[4] quaternion # unit quaternion +float32[3] angular_velocity # angular velocity in radians/second + +``` diff --git a/docs/en/msg_docs/VehicleAttitudeSetpoint.md b/docs/en/msg_docs/VehicleAttitudeSetpoint.md index 4237390400..69552e23ef 100644 --- a/docs/en/msg_docs/VehicleAttitudeSetpoint.md +++ b/docs/en/msg_docs/VehicleAttitudeSetpoint.md @@ -5,7 +5,7 @@ [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) ```c -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # time since system start (microseconds) @@ -18,10 +18,6 @@ float32[4] q_d # Desired quaternion for quaternion control # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] -bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) - -bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) - # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint ``` diff --git a/docs/en/msg_docs/VehicleAttitudeSetpointV0.md b/docs/en/msg_docs/VehicleAttitudeSetpointV0.md new file mode 100644 index 0000000000..9b3a8c655e --- /dev/null +++ b/docs/en/msg_docs/VehicleAttitudeSetpointV0.md @@ -0,0 +1,27 @@ +# VehicleAttitudeSetpointV0 (UORB message) + + + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 yaw_sp_move_rate # rad/s (commanded by user) + +# For quaternion-based attitude control +float32[4] q_d # Desired quaternion for quaternion control + +# For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. +# For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. +float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] + +bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) + +bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) + +# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint + +``` diff --git a/docs/en/msg_docs/VehicleCommand.md b/docs/en/msg_docs/VehicleCommand.md index c2cc25f241..19557cf496 100644 --- a/docs/en/msg_docs/VehicleCommand.md +++ b/docs/en/msg_docs/VehicleCommand.md @@ -11,127 +11,127 @@ Follows the MAVLink COMMAND_INT / COMMAND_LONG definition uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start. -uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command -uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command -uint16 VEHICLE_CMD_CUSTOM_2 = 2 # test command -uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |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_PRECLAND = 23 # Attempt a precision landing -uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |Major Radius [m] |Minor Radius [m] |Velocity [m/s] |Orientation |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| -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_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_CONDITION_GATE = 4501 # Wait until passing a threshold |2D coord mode: 0: Orthogonal to planned route | Altitude mode: 0: Ignore altitude| Empty| Empty| Lat| Lon| Alt| -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 cycles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| 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_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value |Altitude| Frame of new altitude | Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1| Actuator 2| Actuator 3| Actuator 4| Actuator 5| Actuator 6| Index| -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 autonomous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |Ground speed [m/s] |Bitmask |Loiter radius [m] for planes |Yaw [deg] |Latitude |Longitude |Altitude | +uint16 VEHICLE_CMD_CUSTOM_0 = 0 # Test command. +uint16 VEHICLE_CMD_CUSTOM_1 = 1 # Test command. +uint16 VEHICLE_CMD_CUSTOM_2 = 2 # Test command. +uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |[s] (decimal) Hold time. (ignored by fixed wing, time to stay at MISSION for rotary wing)|[m] Acceptance radius (if the sphere with this radius is hit, the MISSION counts as reached)|0 to pass through the WP, if > 0 radius [m] to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.|Desired yaw angle at MISSION (rotary wing)|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time. |Unused|Unused|[m] Radius around MISSION. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns. |Turns|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for time. |[s] Seconds (decimal)|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand. |Unused (FW pitch from FW_TKO_PITCH_MIN)|Unused|Unused|[deg] [@range 0,360] Yaw angle in NED if yaw source available, ignored otherwise|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude AMSL| +uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing. +uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |[m] Radius|[m/s] Velocity|[@enum ORBIT_YAW_BEHAVIOUR] Yaw behaviour|Unused|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |[m] Major radius|[m] Minor radius|[m/s] Velocity|Orientation|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| +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|Unused|[deg] [@range 0, 360] Yaw angle at goal, in compass degrees|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|Unused|Unused|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. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min AMSL - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time. |[s] Delay (decimal, -1 to enable time-of-day fields)|[h] hour (24h format, UTC, -1 to ignore)|minute (24h format, UTC, -1 to ignore)|second (24h format, UTC)|Unused|Unused|Unused| +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.|Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |[s] Delay (decimal seconds)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached.|Descent / Ascend rate (m/s)|Unused|Unused|Unused|Unused|Unused|Finish Altitude| +uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance [m]|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |[deg] [@range 0,360] Target angle. 0 is north|[deg/s] Speed during yaw change|[@range -1,1] Direction: negative: counter clockwise, positive: clockwise |[ 1,0] Relative offset or absolute angle|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_GATE = 4501 # Wait until passing a threshold. |2D coord mode: 0: Orthogonal to planned route|Altitude mode: 0: Ignore altitude|Unused|Unused|Lat|Lon|Alt| +uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE|Unused|Unused|Unused|Unused|Unused|Unused| +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|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |[@enum SPEED_TYPE] Speed type (0=Airspeed, 1=Ground Speed)|Speed (m/s, -1 indicates no change)|[%] Throttle ( Percent, -1 indicates no change)|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|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|Unused|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cycles with a desired period. |Relay number|Cycle count|[s] Cycle time (decimal seconds)|Unused|Unused|Unused|Unused| +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|[us] PWM rate (1000 to 2000 typical)|Cycle count|[s] Cycle time|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately. |Flight termination activated if > 0.5|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value. |Altitude|Frame of new altitude|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1|Actuator 2|Actuator 3|Actuator 4|Actuator 5|Actuator 6|Index| +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. |Unused|Unused|Unused|Unused|Latitude|Longitude|Unused| +uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonomous landing. |[m] Altitude|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |[m/s] Ground speed|Bitmask|[m] Loiter radius for planes|[deg] Yaw|Latitude|Longitude|Altitude| uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193 -uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint| -uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| +uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Pitch offset from next waypoint|Roll offset from next waypoint|Yaw offset from next waypoint| +uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)|Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw|Transmission mode: 0: video stream, >0: single images every n seconds (decimal seconds)|Recording: 0: disabled, 1: enabled compressed, 2: enabled raw|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| uint16 VEHICLE_CMD_DO_DIGICAM_CONTROL=203 -uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # motor test command |Instance (1, ...)| throttle type| throttle| timeout [s]| Motor count | Test order| Empty| -uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # 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_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See mavlink spec MAV_CMD_PREFLIGHT_CALIBRATION -uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration -uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| -uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started -uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty| -uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode |MAV_STANDARD_MODE| -uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal +uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount. |[@enum MAV_MOUNT_MODE] Mount operation mode|Stabilize roll? (1 = yes, 0 = no)|Stabilize pitch? (1 = yes, 0 = no)|stabilize yaw? (1 = yes, 0 = no)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount. |[deg] Pitch or lat, depending on mount mode.|[deg] Roll or lon depending on mount mode|[deg]/[m] Yaw or alt depending on mount mode|Unused|Unused|Unused|[@enum MAV_MOUNT_MODE]| +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence. |enable? (0=disable, 1=enable)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute. |action [@enum PARACHUTE_ACTION] (0=disable, 1=enable, 2=release, for some systems see [@enum PARACHUTE_ACTION], not in general message set.)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # Motor test command. |Instance (@range 1, )|throttle type|throttle|timeout [s]|Motor count|Test order|Unused| +uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight. |inverted (0=normal, 1=inverted)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper. +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight. |[m] Camera trigger distance|Shutter integration time (ms)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)|q2 - quaternion param #2, x (0 in null-rotation)|q3 - quaternion param #3, y (0 in null-rotation)|q4 - quaternion param #4, z (0 in null-rotation)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min(AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See MAVLink spec MAV_CMD_PREFLIGHT_CALIBRATION. +uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# Param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration. +uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow|X axis offset (or generic dimension 1), in the sensor's raw units|Y axis offset (or generic dimension 2), in the sensor's raw units|Z axis offset (or generic dimension 3), in the sensor's raw units|Generic dimension 4, in the sensor's raw units|Generic dimension 5, in the sensor's raw units|Generic dimension 6, in the sensor's raw units| +uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started. +uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.|0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Camera minimum trigger interval|Number of positions|Roll|Pitch|Unused| +uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode. |MAV_STANDARD_MODE| +uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal. -uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| -uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command|value [-1,1]|timeout [s]|Empty|Empty|output function| -uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|configuration|Empty|Empty|Empty|output function| -uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm -uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. -uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes -uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| -uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message -uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| -uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.) -uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom +uint16 VEHICLE_CMD_MISSION_START = 300 # Start running a mission. |first_item: the first mission item to run|last_item: the last mission item to run (after this item is run, the mission ends)| +uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command. |[@range -1,1] value|[s] timeout|Unused|Unused|output function| +uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command. |configuration|Unused|Unused|Unused|output function| +uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component. |1 to arm, 0 to disarm. +uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. +uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes. +uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing. |0:Spektrum|0:Spektrum DSM2, 1:Spektrum DSMX| +uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message. +uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities|Reserved (all remaining params)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)| +uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). +uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control -uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. -uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system -uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. -uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. -uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data -uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data -uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link -uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition -uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization -uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan -uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment -uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. -uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. +uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. +uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. +uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. +uint16 VEHICLE_CMD_LOGGING_START = 2510 # Start streaming ULog data. +uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # Stop streaming ULog data. +uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # Control starting/stopping transmitting data over the high latency link. +uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition. +uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization. +uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan. +uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment. +uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. +uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. -uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # external reset of estimator global position when deadreckoning +uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # External reset of estimator global position when dead reckoning. uint16 VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE = 43004 -# PX4 vehicle commands (beyond 16 bit mavlink commands) -uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX) -uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude| -uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty| +# PX4 vehicle commands (beyond 16 bit MAVLink commands). +uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # Start of PX4 internal only vehicle commands (> UINT16_MAX). +uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Unused|Unused|Unused|Unused|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude (AMSL from GNSS, positive above ground)| +uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Unused|Unused|Unused|Unused|Unused|Unused| -uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization | -uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | -uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt | -uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # +uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization. +uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt. +uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # -uint8 VEHICLE_ROI_NONE = 0 # No region of interest | -uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | -uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | -uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | -uint8 VEHICLE_ROI_TARGET = 4 # Point toward target +uint8 VEHICLE_ROI_NONE = 0 # No region of interest. +uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION. +uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION. +uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location. +uint8 VEHICLE_ROI_TARGET = 4 # Point toward target. uint8 VEHICLE_ROI_ENUM_END = 5 uint8 PARACHUTE_ACTION_DISABLE = 0 @@ -163,13 +163,13 @@ uint8 FAILURE_TYPE_SLOW = 5 uint8 FAILURE_TYPE_DELAYED = 6 uint8 FAILURE_TYPE_INTERMITTENT = 7 -# used as param1 in DO_CHANGE_SPEED command +# Used as param1 in DO_CHANGE_SPEED command. uint8 SPEED_TYPE_AIRSPEED = 0 uint8 SPEED_TYPE_GROUNDSPEED = 1 uint8 SPEED_TYPE_CLIMB_SPEED = 2 uint8 SPEED_TYPE_DESCEND_SPEED = 3 -# used as param3 in CMD_DO_ORBIT +# Used as param3 in CMD_DO_ORBIT. uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0 uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 @@ -177,29 +177,29 @@ uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 -# used as param1 in ARM_DISARM command +# Used as param1 in ARM_DISARM command. int8 ARMING_ACTION_DISARM = 0 int8 ARMING_ACTION_ARM = 1 -# param2 in VEHICLE_CMD_DO_GRIPPER +# param2 in VEHICLE_CMD_DO_GRIPPER. uint8 GRIPPER_ACTION_RELEASE = 0 uint8 GRIPPER_ACTION_GRAB = 1 uint8 ORB_QUEUE_LENGTH = 8 -float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. -uint32 command # Command ID -uint8 target_system # System which should execute the command -uint8 target_component # Component which should execute the command, 0 for all components -uint8 source_system # System sending the command -uint16 source_component # Component / mode executor sending the command -uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. +uint32 command # Command ID. +uint8 target_system # System which should execute the command. +uint8 target_component # Component which should execute the command, 0 for all components. +uint8 source_system # System sending the command. +uint16 source_component # Component / mode executor sending the command. +uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command). bool from_external uint16 COMPONENT_MODE_EXECUTOR_START = 1000 diff --git a/docs/en/msg_docs/index.md b/docs/en/msg_docs/index.md index fdfe25731b..0904013766 100644 --- a/docs/en/msg_docs/index.md +++ b/docs/en/msg_docs/index.md @@ -15,10 +15,18 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message +- [AirspeedValidated](AirspeedValidated.md) - [ArmingCheckReply](ArmingCheckReply.md) - [ArmingCheckRequest](ArmingCheckRequest.md) - [BatteryStatus](BatteryStatus.md) - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors +- [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message +Used by the fw_lateral_longitudinal_control module +At least one of course, airspeed_direction, or lateral_acceleration must be finite. +- [FixedWingLongitudinalSetpoint](FixedWingLongitudinalSetpoint.md) — Fixed Wing Longitudinal Setpoint message +Used by the fw_lateral_longitudinal_control module +If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +If both altitude and height_rate are NAN, the controller maintains the current altitude. - [GotoSetpoint](GotoSetpoint.md) — Position and (optional) heading setpoints with corresponding speed constraints Setpoints are intended as inputs to position and heading smoothers, respectively Setpoints do not need to be kinematically consistent @@ -26,6 +34,11 @@ Optional heading setpoints may be specified as controlled by the respective flag Unset optional setpoints are not controlled Unset optional constraints default to vehicle specifications - [HomePosition](HomePosition.md) — GPS home position in WGS84 coordinates. +- [LateralControlConfiguration](LateralControlConfiguration.md) — Fixed Wing Lateral Control Configuration message +Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. +- [LongitudinalControlConfiguration](LongitudinalControlConfiguration.md) — Fixed Wing Longitudinal Control Configuration message +Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +and configure the resultant setpoints. - [ManualControlSetpoint](ManualControlSetpoint.md) - [ModeCompleted](ModeCompleted.md) — Mode completion result, published by an active mode. The possible values of nav_state are defined in the VehicleStatus msg. @@ -72,7 +85,6 @@ The coordinate system origin is the vehicle position at the time when the EKF2-m - [ActuatorTest](ActuatorTest.md) - [AdcReport](AdcReport.md) - [Airspeed](Airspeed.md) -- [AirspeedValidated](AirspeedValidated.md) - [AirspeedWind](AirspeedWind.md) - [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) - [ButtonEvent](ButtonEvent.md) @@ -80,7 +92,7 @@ The coordinate system origin is the vehicle position at the time when the EKF2-m - [CameraStatus](CameraStatus.md) - [CameraTrigger](CameraTrigger.md) - [CanInterfaceStatus](CanInterfaceStatus.md) -- [CellularStatus](CellularStatus.md) +- [CellularStatus](CellularStatus.md) — Cellular status - [CollisionConstraints](CollisionConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided - [ControlAllocatorStatus](ControlAllocatorStatus.md) @@ -116,6 +128,11 @@ scale errors, in-run bias and thermal drift (if thermal compensation is enabled - [FailsafeFlags](FailsafeFlags.md) — Input flags for the failsafe state machine set by the arming & health checks. - [FailureDetectorStatus](FailureDetectorStatus.md) - [FigureEightStatus](FigureEightStatus.md) +- [FixedWingLateralGuidanceStatus](FixedWingLateralGuidanceStatus.md) — Fixed Wing Lateral Guidance Status message +Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs +- [FixedWingLateralStatus](FixedWingLateralStatus.md) — Fixed Wing Lateral Status message +Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint +- [FixedWingRunwayControl](FixedWingRunwayControl.md) — Auxiliary control fields for fixed-wing runway takeoff/landing - [FlightPhaseEstimation](FlightPhaseEstimation.md) - [FollowTarget](FollowTarget.md) - [FollowTargetEstimator](FollowTargetEstimator.md) @@ -170,7 +187,6 @@ These are the externally visible LED's, not the board LED's - [NavigatorStatus](NavigatorStatus.md) — Current status of a Navigator mode The possible values of nav_state are defined in the VehicleStatus msg. - [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md) -- [NpfgStatus](NpfgStatus.md) - [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor. - [OffboardControlMode](OffboardControlMode.md) — Off-board control mode - [OnboardComputerStatus](OnboardComputerStatus.md) — ONBOARD_COMPUTER_STATUS message data @@ -207,10 +223,12 @@ This are the three next waypoints (or just the next two or one). - [RcParameterMap](RcParameterMap.md) - [RoverAttitudeSetpoint](RoverAttitudeSetpoint.md) - [RoverAttitudeStatus](RoverAttitudeStatus.md) +- [RoverPositionSetpoint](RoverPositionSetpoint.md) - [RoverRateSetpoint](RoverRateSetpoint.md) - [RoverRateStatus](RoverRateStatus.md) - [RoverSteeringSetpoint](RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) +- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) - [RoverVelocityStatus](RoverVelocityStatus.md) - [Rpm](Rpm.md) - [RtlStatus](RtlStatus.md) @@ -248,6 +266,8 @@ such as Pozyx or NXP Rddrone. - [TelemetryStatus](TelemetryStatus.md) - [TiltrotorExtraControls](TiltrotorExtraControls.md) - [TimesyncStatus](TimesyncStatus.md) +- [TrajectorySetpoint6dof](TrajectorySetpoint6dof.md) — Trajectory setpoint in NED frame +Input to position controller. - [TransponderReport](TransponderReport.md) - [TuneControl](TuneControl.md) — 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. @@ -277,6 +297,8 @@ NaN means the state was not controlled - [WheelEncoders](WheelEncoders.md) - [Wind](Wind.md) - [YawEstimatorStatus](YawEstimatorStatus.md) +- [AirspeedValidatedV0](AirspeedValidatedV0.md) +- [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander \ No newline at end of file diff --git a/docs/en/telemetry/crsf_telemetry.md b/docs/en/telemetry/crsf_telemetry.md index a691778921..98f1e4507e 100644 --- a/docs/en/telemetry/crsf_telemetry.md +++ b/docs/en/telemetry/crsf_telemetry.md @@ -71,7 +71,7 @@ For ExpressLRS receivers wire to the flight controller UART as shown below (wiri ### Firmware Configuration/Build CRSF telemetry support is not included in any PX4 firmware by default. -To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver.md#crsf-rc) and removes [rc_input](../modules/modules_driver.md#rc-input). +To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver_radio_control.md#crsf-rc) and removes [rc_input](../modules/modules_driver_radio_control.md#rc-input). The steps are: diff --git a/docs/en/tutorials/linux_sbus.md b/docs/en/tutorials/linux_sbus.md index 0569f7111e..6df65ca508 100644 --- a/docs/en/tutorials/linux_sbus.md +++ b/docs/en/tutorials/linux_sbus.md @@ -10,9 +10,7 @@ For an S.Bus receiver (or encoder - e.g. from Futaba, RadioLink, etc.) you will Then [Start the PX4 RC Driver](#start_driver) on the device, as shown below. - - -## Starting the Driver +## Starting the Driver {#start_driver} To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): @@ -20,11 +18,9 @@ To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): rc_input start -d /dev/ttyS2 ``` -For other driver usage information see: [rc_input](../modules/modules_driver.md#rc-input). +For other driver usage information see: [rc_input](../modules/modules_driver_radio_control.md#rc-input). - - -## Signal Inverter Circuit (S.Bus only) +## Signal Inverter Circuit (S.Bus only) {#signal_inverter_circuit} S.Bus is an _inverted_ UART communication signal. diff --git a/docs/public/config/failsafe/index.js b/docs/public/config/failsafe/index.js index b557d6fc05..5702f7fec6 100644 --- a/docs/public/config/failsafe/index.js +++ b/docs/public/config/failsafe/index.js @@ -1 +1 @@ -var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof WorkerGlobalScope!="undefined";var ENVIRONMENT_IS_NODE=typeof process=="object"&&process.versions?.node&&process.type!="renderer";if(ENVIRONMENT_IS_NODE){}var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var _scriptName=typeof document!="undefined"?document.currentScript?.src:undefined;if(typeof __filename!="undefined"){_scriptName=__filename}else if(ENVIRONMENT_IS_WORKER){_scriptName=self.location.href}var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");var nodePath=require("path");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename);return ret};readAsync=async(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename,binary?undefined:"utf8");return ret};if(process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){try{scriptDirectory=new URL(".",_scriptName).href}catch{}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=async url=>{if(isFileURI(url)){return new Promise((resolve,reject)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response);return}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}var response=await fetch(url,{credentials:"same-origin"});if(response.ok){return response.arrayBuffer()}throw new Error(response.status+" : "+response.url)}}}else{}var out=console.log.bind(console);var err=console.error.bind(console);var wasmBinary;var wasmMemory;var ABORT=false;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAP64,HEAPU64,HEAPF64;var runtimeInitialized=false;var isFileURI=filename=>filename.startsWith("file://");function updateMemoryViews(){var b=wasmMemory.buffer;HEAP8=new Int8Array(b);HEAP16=new Int16Array(b);HEAPU8=new Uint8Array(b);HEAPU16=new Uint16Array(b);HEAP32=new Int32Array(b);HEAPU32=new Uint32Array(b);HEAPF32=new Float32Array(b);HEAPF64=new Float64Array(b);HEAP64=new BigInt64Array(b);HEAPU64=new BigUint64Array(b)}function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(onPreRuns)}function initRuntime(){runtimeInitialized=true;wasmExports["v"]()}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(onPostRuns)}var runDependencies=0;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var wasmBinaryFile;function findWasmBinary(){return locateFile("index.wasm")}function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}async function getWasmBinary(binaryFile){if(!wasmBinary){try{var response=await readAsync(binaryFile);return new Uint8Array(response)}catch{}}return getBinarySync(binaryFile)}async function instantiateArrayBuffer(binaryFile,imports){try{var binary=await getWasmBinary(binaryFile);var instance=await WebAssembly.instantiate(binary,imports);return instance}catch(reason){err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)}}async function instantiateAsync(binary,binaryFile,imports){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE){try{var response=fetch(binaryFile,{credentials:"same-origin"});var instantiationResult=await WebAssembly.instantiateStreaming(response,imports);return instantiationResult}catch(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation")}}return instantiateArrayBuffer(binaryFile,imports)}function getWasmImports(){return{a:wasmImports}}async function createWasm(){function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["u"];updateMemoryViews();wasmTable=wasmExports["A"];removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){return receiveInstance(result["instance"])}var info=getWasmImports();if(Module["instantiateWasm"]){return new Promise((resolve,reject)=>{Module["instantiateWasm"](info,(mod,inst)=>{resolve(receiveInstance(mod,inst))})})}wasmBinaryFile??=findWasmBinary();var result=await instantiateAsync(wasmBinary,wasmBinaryFile,info);var exports=receiveInstantiationResult(result);return exports}class ExitStatus{name="ExitStatus";constructor(status){this.message=`Program terminated with exit(${status})`;this.status=status}}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var onPostRuns=[];var addOnPostRun=cb=>onPostRuns.push(cb);var onPreRuns=[];var addOnPreRun=cb=>onPreRuns.push(cb);var noExitRuntime=true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>abort("");var embind_init_charCodes=()=>{var codes=new Array(256);for(var i=0;i<256;++i){codes[i]=String.fromCharCode(i)}embind_charCodes=codes};var embind_charCodes;var readLatin1String=ptr=>{var ret="";var c=ptr;while(HEAPU8[c]){ret+=embind_charCodes[HEAPU8[c++]]}return ret};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};var throwBindingError=message=>{throw new BindingError(message)};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){return sharedRegisterType(rawType,registeredInstance,options)}var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];case 8:return signed?pointer=>HEAP64[pointer>>3]:pointer=>HEAPU64[pointer>>3];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);const isUnsignedType=minRange===0n;let fromWireType=value=>value;if(isUnsignedType){const bitSize=size*8;fromWireType=value=>BigInt.asUintN(bitSize,value);maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>{if(typeof value=="number"){value=BigInt(value)}return value},argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,!isUnsignedType),destructorFunction:null})};var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var init_ClassHandle=()=>{let proto=ClassHandle.prototype;Object.assign(proto,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}});const symbolDispose=Symbol.dispose;if(symbolDispose){proto[symbolDispose]=proto["delete"]}};function ClassHandle(){}var createNamedFunction=(name,func)=>Object.defineProperty(func,"name",{value:name});var registeredPointers={};var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module[name].overloadTable.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var InternalError=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};var throwInternalError=message=>{throw new InternalError(message)};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var embind__requireFunction=(signature,rawFunction,isAsync=false)=>{signature=readLatin1String(signature);function makeDynCaller(){var rtn=getWasmTableEntry(rawFunction);return rtn}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};class UnboundTypeError extends Error{}var getTypeName=type=>{var ptr=___getTypeName(type);var rv=readLatin1String(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(type=>typeDependencies[type]=dependentTypes);function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=readLatin1String(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError(`Use 'new' to construct ${name}`)}if(undefined===registeredClass.constructor_body){throw new BindingError(`${name} has no accessible constructor`)}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex===-1)return signature;return signature.slice(0,argsIndex)};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync,isNonnullReturn)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=readLatin1String(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker,isAsync);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=readLatin1String(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[0,1,,1,null,1,true,1,false,1];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var Emval={toValue:handle=>{if(!handle){throwBindingError(`Cannot use deleted val. handle = ${handle}`)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync,isNonnullReturn)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=readLatin1String(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker,isAsync);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);const isUnsignedType=minRange===0;let fromWireType=value=>value;if(isUnsignedType){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift;maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array,BigInt64Array,BigUint64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=readLatin1String(name);registerType(rawType,{name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=55296&&u<=57343){var u1=str.charCodeAt(++i);u=65536+((u&1023)<<10)|u1&1023}if(u<=127){if(outIdx>=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx=0,maxBytesToRead=NaN)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=readLatin1String(name);var stdStringIsUTF8=true;registerType(rawType,{name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(valueIsOfTypeString){if(stdStringIsUTF8){stringToUTF8(value,ptr,length+1)}else{for(var i=0;i255){_free(base);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}}else{HEAPU8.set(value,ptr)}if(destructors!==null){destructors.push(_free,base)}return base},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var UTF16Decoder=typeof TextDecoder!="undefined"?new TextDecoder("utf-16le"):undefined;var UTF16ToString=(ptr,maxBytesToRead)=>{var idx=ptr>>1;var maxIdx=idx+maxBytesToRead/2;var endIdx=idx;while(!(endIdx>=maxIdx)&&HEAPU16[endIdx])++endIdx;if(endIdx-idx>16&&UTF16Decoder)return UTF16Decoder.decode(HEAPU16.subarray(idx,endIdx));var str="";for(var i=idx;!(i>=maxIdx);++i){var codeUnit=HEAPU16[i];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var i=0;var str="";while(!(i>=maxBytesToRead/4)){var utf32=HEAP32[ptr+i*4>>2];if(utf32==0)break;++i;if(utf32>=65536){var ch=utf32-65536;str+=String.fromCharCode(55296|ch>>10,56320|ch&1023)}else{str+=String.fromCharCode(utf32)}}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i=55296&&codeUnit<=57343){var trailSurrogate=str.charCodeAt(++i);codeUnit=65536+((codeUnit&1023)<<10)|trailSurrogate&1023}HEAP32[outPtr>>2]=codeUnit;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i=55296&&codeUnit<=57343)++i;len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=readLatin1String(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=readLatin1String(name);registerType(rawType,{isVoid:true,name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};embind_init_charCodes();init_ClassHandle();init_RegisteredPointer();{if(Module["noExitRuntime"])noExitRuntime=Module["noExitRuntime"];if(Module["print"])out=Module["print"];if(Module["printErr"])err=Module["printErr"];if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"]}var wasmImports={f:___cxa_throw,p:__abort_js,k:__embind_register_bigint,m:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,r:__embind_register_emval,j:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,s:__embind_register_std_string,g:__embind_register_std_wstring,n:__embind_register_void,o:__emval_take_value,t:_emscripten_date_now,q:_emscripten_resize_heap,i:_fd_write};var wasmExports;createWasm();var ___wasm_call_ctors=()=>(___wasm_call_ctors=wasmExports["v"])();var _param_get=Module["_param_get"]=(a0,a1)=>(_param_get=Module["_param_get"]=wasmExports["w"])(a0,a1);var _param_set_used=Module["_param_set_used"]=a0=>(_param_set_used=Module["_param_set_used"]=wasmExports["x"])(a0);var __Znwm=Module["__Znwm"]=a0=>(__Znwm=Module["__Znwm"]=wasmExports["y"])(a0);var __ZdlPvm=Module["__ZdlPvm"]=(a0,a1)=>(__ZdlPvm=Module["__ZdlPvm"]=wasmExports["z"])(a0,a1);var _malloc=a0=>(_malloc=wasmExports["B"])(a0);var __ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=a0=>(__ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=wasmExports["C"])(a0);var ___cxa_allocate_exception=Module["___cxa_allocate_exception"]=a0=>(___cxa_allocate_exception=Module["___cxa_allocate_exception"]=wasmExports["D"])(a0);var __ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=a0=>(__ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=wasmExports["E"])(a0);var __ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=a0=>(__ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=wasmExports["F"])(a0);var __ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=a0=>(__ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=wasmExports["G"])(a0);var ___cxa_pure_virtual=Module["___cxa_pure_virtual"]=()=>(___cxa_pure_virtual=Module["___cxa_pure_virtual"]=wasmExports["H"])();var ___getTypeName=a0=>(___getTypeName=wasmExports["I"])(a0);var __ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=a0=>(__ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=wasmExports["J"])(a0);var __emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=(a0,a1,a2)=>(__emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=wasmExports["K"])(a0,a1,a2);var _emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=()=>(_emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=wasmExports["L"])();var _emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=()=>(_emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=wasmExports["M"])();var _free=a0=>(_free=wasmExports["N"])(a0);var _emscripten_stack_init=Module["_emscripten_stack_init"]=()=>(_emscripten_stack_init=Module["_emscripten_stack_init"]=wasmExports["O"])();var _emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=(a0,a1)=>(_emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=wasmExports["P"])(a0,a1);var _emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=()=>(_emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=wasmExports["Q"])();var __ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=()=>(__ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=wasmExports["R"])();var __Znam=Module["__Znam"]=a0=>(__Znam=Module["__Znam"]=wasmExports["S"])(a0);var __ZdlPv=Module["__ZdlPv"]=a0=>(__ZdlPv=Module["__ZdlPv"]=wasmExports["T"])(a0);var __ZdaPv=Module["__ZdaPv"]=a0=>(__ZdaPv=Module["__ZdaPv"]=wasmExports["U"])(a0);var __ZdaPvm=Module["__ZdaPvm"]=(a0,a1)=>(__ZdaPvm=Module["__ZdaPvm"]=wasmExports["V"])(a0,a1);var __ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=(a0,a1)=>(__ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=wasmExports["W"])(a0,a1);var __ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=(a0,a1)=>(__ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=wasmExports["X"])(a0,a1);var __ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=(a0,a1)=>(__ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=wasmExports["Y"])(a0,a1);var __ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=wasmExports["Z"])(a0,a1,a2);var __ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=(a0,a1)=>(__ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=wasmExports["_"])(a0,a1);var __ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=wasmExports["$"])(a0,a1,a2);var __ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=a0=>(__ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=wasmExports["aa"])(a0);var __ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=a0=>(__ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=wasmExports["ba"])(a0);var __ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=a0=>(__ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=wasmExports["ca"])(a0);var __ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=()=>(__ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=wasmExports["da"])();var __ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=()=>(__ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=wasmExports["ea"])();var __ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=()=>(__ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=wasmExports["fa"])();var __ZSt9terminatev=Module["__ZSt9terminatev"]=()=>(__ZSt9terminatev=Module["__ZSt9terminatev"]=wasmExports["ga"])();var ___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=()=>(___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=wasmExports["ha"])();var ___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=a0=>(___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=wasmExports["ia"])(a0);var ___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=()=>(___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=wasmExports["ja"])();var ___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=()=>(___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=wasmExports["ka"])();var ___cxa_free_exception=Module["___cxa_free_exception"]=a0=>(___cxa_free_exception=Module["___cxa_free_exception"]=wasmExports["la"])(a0);var ___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=(a0,a1,a2)=>(___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=wasmExports["ma"])(a0,a1,a2);var ___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=()=>(___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=wasmExports["na"])();var ___dynamic_cast=Module["___dynamic_cast"]=(a0,a1,a2,a3)=>(___dynamic_cast=Module["___dynamic_cast"]=wasmExports["oa"])(a0,a1,a2,a3);var __ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=a0=>(__ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=wasmExports["pa"])(a0);var __ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=a0=>(__ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=wasmExports["qa"])(a0);var __ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=a0=>(__ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=wasmExports["ra"])(a0);var __ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=a0=>(__ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=wasmExports["sa"])(a0);var __ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=a0=>(__ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=wasmExports["ta"])(a0);var __ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=a0=>(__ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=wasmExports["ua"])(a0);var __ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=a0=>(__ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=wasmExports["va"])(a0);var __ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=a0=>(__ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=wasmExports["wa"])(a0);var __ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=a0=>(__ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=wasmExports["xa"])(a0);var __ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=a0=>(__ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=wasmExports["ya"])(a0);var __ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=a0=>(__ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=wasmExports["za"])(a0);var __ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=a0=>(__ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=wasmExports["Aa"])(a0);var __ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=a0=>(__ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=wasmExports["Ba"])(a0);var __ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=a0=>(__ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=wasmExports["Ca"])(a0);var __ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=a0=>(__ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=wasmExports["Da"])(a0);var __ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=a0=>(__ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=wasmExports["Ea"])(a0);var __ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=a0=>(__ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=wasmExports["Fa"])(a0);var __ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=a0=>(__ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=wasmExports["Ga"])(a0);var __ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=a0=>(__ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=wasmExports["Ha"])(a0);var __ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=a0=>(__ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=wasmExports["Ia"])(a0);var __ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=a0=>(__ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=wasmExports["Ja"])(a0);var __ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=a0=>(__ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=wasmExports["Ka"])(a0);var __ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=a0=>(__ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=wasmExports["La"])(a0);var __ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=a0=>(__ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=wasmExports["Ma"])(a0);var __ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=a0=>(__ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=wasmExports["Na"])(a0);var __ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=a0=>(__ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=wasmExports["Oa"])(a0);var __ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=a0=>(__ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=wasmExports["Pa"])(a0);var __ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=a0=>(__ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=wasmExports["Qa"])(a0);var __ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=a0=>(__ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=wasmExports["Ra"])(a0);var __ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=a0=>(__ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=wasmExports["Sa"])(a0);var __ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=a0=>(__ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=wasmExports["Ta"])(a0);var __ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=a0=>(__ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=wasmExports["Ua"])(a0);var __ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=a0=>(__ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=wasmExports["Va"])(a0);var __ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=a0=>(__ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=wasmExports["Wa"])(a0);var __ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=a0=>(__ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=wasmExports["Xa"])(a0);var __ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=a0=>(__ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=wasmExports["Ya"])(a0);var __ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=a0=>(__ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=wasmExports["Za"])(a0);var __ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=a0=>(__ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=wasmExports["_a"])(a0);var __ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=a0=>(__ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=wasmExports["$a"])(a0);var __ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=a0=>(__ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=wasmExports["ab"])(a0);var __ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=a0=>(__ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=wasmExports["bb"])(a0);var __ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=a0=>(__ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=wasmExports["cb"])(a0);var __ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=a0=>(__ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=wasmExports["db"])(a0);var __ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=a0=>(__ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=wasmExports["eb"])(a0);var __ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=a0=>(__ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=wasmExports["fb"])(a0);var __ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=a0=>(__ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=wasmExports["gb"])(a0);var __ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=a0=>(__ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=wasmExports["hb"])(a0);var __ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=a0=>(__ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=wasmExports["ib"])(a0);var __ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=a0=>(__ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=wasmExports["jb"])(a0);var __ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=a0=>(__ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=wasmExports["kb"])(a0);var __ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=a0=>(__ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=wasmExports["lb"])(a0);var __ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=a0=>(__ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=wasmExports["mb"])(a0);var __ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=a0=>(__ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=wasmExports["nb"])(a0);var __ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=a0=>(__ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=wasmExports["ob"])(a0);var __ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=a0=>(__ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=wasmExports["pb"])(a0);var __ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=a0=>(__ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=wasmExports["qb"])(a0);var __ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=a0=>(__ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=wasmExports["rb"])(a0);var __ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=a0=>(__ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=wasmExports["sb"])(a0);var __ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=a0=>(__ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=wasmExports["tb"])(a0);var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=47520;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=47504;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=47496;var __ZTIb=Module["__ZTIb"]=30340;var __ZTIh=Module["__ZTIh"]=30496;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47676;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47660;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47608;var __ZTISt12length_error=Module["__ZTISt12length_error"]=32440;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=32420;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=32204;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=47596;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=32492;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=32472;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=31772;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=31864;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=31732;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28075;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=31984;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28094;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28114;var __ZTIi=Module["__ZTIi"]=30704;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28163;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28230;var __ZTIv=Module["__ZTIv"]=30232;var __ZTIf=Module["__ZTIf"]=31176;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28328;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28415;var __ZTIm=Module["__ZTIm"]=30860;var __ZTIN10emscripten3valE=Module["__ZTIN10emscripten3valE"]=47748;var __ZTSN10emscripten3valE=Module["__ZTSN10emscripten3valE"]=28518;var __ZTIc=Module["__ZTIc"]=30444;var __ZTIa=Module["__ZTIa"]=30548;var __ZTIs=Module["__ZTIs"]=30600;var __ZTIt=Module["__ZTIt"]=30652;var __ZTIj=Module["__ZTIj"]=30756;var __ZTIl=Module["__ZTIl"]=30808;var __ZTIx=Module["__ZTIx"]=30912;var __ZTIy=Module["__ZTIy"]=30964;var __ZTId=Module["__ZTId"]=31228;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28572;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28644;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28720;var __ZTIN10emscripten11memory_viewIcEE=Module["__ZTIN10emscripten11memory_viewIcEE"]=28796;var __ZTIN10emscripten11memory_viewIaEE=Module["__ZTIN10emscripten11memory_viewIaEE"]=28836;var __ZTIN10emscripten11memory_viewIhEE=Module["__ZTIN10emscripten11memory_viewIhEE"]=28876;var __ZTIN10emscripten11memory_viewIsEE=Module["__ZTIN10emscripten11memory_viewIsEE"]=28916;var __ZTIN10emscripten11memory_viewItEE=Module["__ZTIN10emscripten11memory_viewItEE"]=28956;var __ZTIN10emscripten11memory_viewIiEE=Module["__ZTIN10emscripten11memory_viewIiEE"]=28996;var __ZTIN10emscripten11memory_viewIjEE=Module["__ZTIN10emscripten11memory_viewIjEE"]=29036;var __ZTIN10emscripten11memory_viewIlEE=Module["__ZTIN10emscripten11memory_viewIlEE"]=29076;var __ZTIN10emscripten11memory_viewImEE=Module["__ZTIN10emscripten11memory_viewImEE"]=29116;var __ZTIN10emscripten11memory_viewIxEE=Module["__ZTIN10emscripten11memory_viewIxEE"]=29156;var __ZTIN10emscripten11memory_viewIyEE=Module["__ZTIN10emscripten11memory_viewIyEE"]=29196;var __ZTIN10emscripten11memory_viewIfEE=Module["__ZTIN10emscripten11memory_viewIfEE"]=29236;var __ZTIN10emscripten11memory_viewIdEE=Module["__ZTIN10emscripten11memory_viewIdEE"]=29276;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28580;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28652;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28728;var __ZTSN10emscripten11memory_viewIcEE=Module["__ZTSN10emscripten11memory_viewIcEE"]=28804;var __ZTSN10emscripten11memory_viewIaEE=Module["__ZTSN10emscripten11memory_viewIaEE"]=28844;var __ZTSN10emscripten11memory_viewIhEE=Module["__ZTSN10emscripten11memory_viewIhEE"]=28884;var __ZTSN10emscripten11memory_viewIsEE=Module["__ZTSN10emscripten11memory_viewIsEE"]=28924;var __ZTSN10emscripten11memory_viewItEE=Module["__ZTSN10emscripten11memory_viewItEE"]=28964;var __ZTSN10emscripten11memory_viewIiEE=Module["__ZTSN10emscripten11memory_viewIiEE"]=29004;var __ZTSN10emscripten11memory_viewIjEE=Module["__ZTSN10emscripten11memory_viewIjEE"]=29044;var __ZTSN10emscripten11memory_viewIlEE=Module["__ZTSN10emscripten11memory_viewIlEE"]=29084;var __ZTSN10emscripten11memory_viewImEE=Module["__ZTSN10emscripten11memory_viewImEE"]=29124;var __ZTSN10emscripten11memory_viewIxEE=Module["__ZTSN10emscripten11memory_viewIxEE"]=29164;var __ZTSN10emscripten11memory_viewIyEE=Module["__ZTSN10emscripten11memory_viewIyEE"]=29204;var __ZTSN10emscripten11memory_viewIfEE=Module["__ZTSN10emscripten11memory_viewIfEE"]=29244;var __ZTSN10emscripten11memory_viewIdEE=Module["__ZTSN10emscripten11memory_viewIdEE"]=29284;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=32244;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32080;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=32264;var __ZTISt9exception=Module["__ZTISt9exception"]=32100;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=47976;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=47972;var ___cxa_new_handler=Module["___cxa_new_handler"]=50220;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=29808;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=29856;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=29904;var __ZTIDn=Module["__ZTIDn"]=30284;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=29952;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=3e4;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=30052;var __ZTISt9type_info=Module["__ZTISt9type_info"]=32764;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=29820;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=29868;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=29916;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=29964;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=30012;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=30064;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=30124;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=30152;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=30180;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=30192;var __ZTSv=Module["__ZTSv"]=30240;var __ZTIPv=Module["__ZTIPv"]=30244;var __ZTSPv=Module["__ZTSPv"]=30260;var __ZTIPKv=Module["__ZTIPKv"]=30264;var __ZTSPKv=Module["__ZTSPKv"]=30280;var __ZTSDn=Module["__ZTSDn"]=30292;var __ZTIPDn=Module["__ZTIPDn"]=30296;var __ZTSPDn=Module["__ZTSPDn"]=30312;var __ZTIPKDn=Module["__ZTIPKDn"]=30316;var __ZTSPKDn=Module["__ZTSPKDn"]=30332;var __ZTSb=Module["__ZTSb"]=30348;var __ZTIPb=Module["__ZTIPb"]=30352;var __ZTSPb=Module["__ZTSPb"]=30368;var __ZTIPKb=Module["__ZTIPKb"]=30372;var __ZTSPKb=Module["__ZTSPKb"]=30388;var __ZTIw=Module["__ZTIw"]=30392;var __ZTSw=Module["__ZTSw"]=30400;var __ZTIPw=Module["__ZTIPw"]=30404;var __ZTSPw=Module["__ZTSPw"]=30420;var __ZTIPKw=Module["__ZTIPKw"]=30424;var __ZTSPKw=Module["__ZTSPKw"]=30440;var __ZTSc=Module["__ZTSc"]=30452;var __ZTIPc=Module["__ZTIPc"]=30456;var __ZTSPc=Module["__ZTSPc"]=30472;var __ZTIPKc=Module["__ZTIPKc"]=30476;var __ZTSPKc=Module["__ZTSPKc"]=30492;var __ZTSh=Module["__ZTSh"]=30504;var __ZTIPh=Module["__ZTIPh"]=30508;var __ZTSPh=Module["__ZTSPh"]=30524;var __ZTIPKh=Module["__ZTIPKh"]=30528;var __ZTSPKh=Module["__ZTSPKh"]=30544;var __ZTSa=Module["__ZTSa"]=30556;var __ZTIPa=Module["__ZTIPa"]=30560;var __ZTSPa=Module["__ZTSPa"]=30576;var __ZTIPKa=Module["__ZTIPKa"]=30580;var __ZTSPKa=Module["__ZTSPKa"]=30596;var __ZTSs=Module["__ZTSs"]=30608;var __ZTIPs=Module["__ZTIPs"]=30612;var __ZTSPs=Module["__ZTSPs"]=30628;var __ZTIPKs=Module["__ZTIPKs"]=30632;var __ZTSPKs=Module["__ZTSPKs"]=30648;var __ZTSt=Module["__ZTSt"]=30660;var __ZTIPt=Module["__ZTIPt"]=30664;var __ZTSPt=Module["__ZTSPt"]=30680;var __ZTIPKt=Module["__ZTIPKt"]=30684;var __ZTSPKt=Module["__ZTSPKt"]=30700;var __ZTSi=Module["__ZTSi"]=30712;var __ZTIPi=Module["__ZTIPi"]=30716;var __ZTSPi=Module["__ZTSPi"]=30732;var __ZTIPKi=Module["__ZTIPKi"]=30736;var __ZTSPKi=Module["__ZTSPKi"]=30752;var __ZTSj=Module["__ZTSj"]=30764;var __ZTIPj=Module["__ZTIPj"]=30768;var __ZTSPj=Module["__ZTSPj"]=30784;var __ZTIPKj=Module["__ZTIPKj"]=30788;var __ZTSPKj=Module["__ZTSPKj"]=30804;var __ZTSl=Module["__ZTSl"]=30816;var __ZTIPl=Module["__ZTIPl"]=30820;var __ZTSPl=Module["__ZTSPl"]=30836;var __ZTIPKl=Module["__ZTIPKl"]=30840;var __ZTSPKl=Module["__ZTSPKl"]=30856;var __ZTSm=Module["__ZTSm"]=30868;var __ZTIPm=Module["__ZTIPm"]=30872;var __ZTSPm=Module["__ZTSPm"]=30888;var __ZTIPKm=Module["__ZTIPKm"]=30892;var __ZTSPKm=Module["__ZTSPKm"]=30908;var __ZTSx=Module["__ZTSx"]=30920;var __ZTIPx=Module["__ZTIPx"]=30924;var __ZTSPx=Module["__ZTSPx"]=30940;var __ZTIPKx=Module["__ZTIPKx"]=30944;var __ZTSPKx=Module["__ZTSPKx"]=30960;var __ZTSy=Module["__ZTSy"]=30972;var __ZTIPy=Module["__ZTIPy"]=30976;var __ZTSPy=Module["__ZTSPy"]=30992;var __ZTIPKy=Module["__ZTIPKy"]=30996;var __ZTSPKy=Module["__ZTSPKy"]=31012;var __ZTIn=Module["__ZTIn"]=31016;var __ZTSn=Module["__ZTSn"]=31024;var __ZTIPn=Module["__ZTIPn"]=31028;var __ZTSPn=Module["__ZTSPn"]=31044;var __ZTIPKn=Module["__ZTIPKn"]=31048;var __ZTSPKn=Module["__ZTSPKn"]=31064;var __ZTIo=Module["__ZTIo"]=31068;var __ZTSo=Module["__ZTSo"]=31076;var __ZTIPo=Module["__ZTIPo"]=31080;var __ZTSPo=Module["__ZTSPo"]=31096;var __ZTIPKo=Module["__ZTIPKo"]=31100;var __ZTSPKo=Module["__ZTSPKo"]=31116;var __ZTIDh=Module["__ZTIDh"]=31120;var __ZTSDh=Module["__ZTSDh"]=31128;var __ZTIPDh=Module["__ZTIPDh"]=31132;var __ZTSPDh=Module["__ZTSPDh"]=31148;var __ZTIPKDh=Module["__ZTIPKDh"]=31152;var __ZTSPKDh=Module["__ZTSPKDh"]=31168;var __ZTSf=Module["__ZTSf"]=31184;var __ZTIPf=Module["__ZTIPf"]=31188;var __ZTSPf=Module["__ZTSPf"]=31204;var __ZTIPKf=Module["__ZTIPKf"]=31208;var __ZTSPKf=Module["__ZTSPKf"]=31224;var __ZTSd=Module["__ZTSd"]=31236;var __ZTIPd=Module["__ZTIPd"]=31240;var __ZTSPd=Module["__ZTSPd"]=31256;var __ZTIPKd=Module["__ZTIPKd"]=31260;var __ZTSPKd=Module["__ZTSPKd"]=31276;var __ZTIe=Module["__ZTIe"]=31280;var __ZTSe=Module["__ZTSe"]=31288;var __ZTIPe=Module["__ZTIPe"]=31292;var __ZTSPe=Module["__ZTSPe"]=31308;var __ZTIPKe=Module["__ZTIPKe"]=31312;var __ZTSPKe=Module["__ZTSPKe"]=31328;var __ZTIg=Module["__ZTIg"]=31332;var __ZTSg=Module["__ZTSg"]=31340;var __ZTIPg=Module["__ZTIPg"]=31344;var __ZTSPg=Module["__ZTSPg"]=31360;var __ZTIPKg=Module["__ZTIPKg"]=31364;var __ZTSPKg=Module["__ZTSPKg"]=31380;var __ZTIDu=Module["__ZTIDu"]=31384;var __ZTSDu=Module["__ZTSDu"]=31392;var __ZTIPDu=Module["__ZTIPDu"]=31396;var __ZTSPDu=Module["__ZTSPDu"]=31412;var __ZTIPKDu=Module["__ZTIPKDu"]=31416;var __ZTSPKDu=Module["__ZTSPKDu"]=31432;var __ZTIDs=Module["__ZTIDs"]=31440;var __ZTSDs=Module["__ZTSDs"]=31448;var __ZTIPDs=Module["__ZTIPDs"]=31452;var __ZTSPDs=Module["__ZTSPDs"]=31468;var __ZTIPKDs=Module["__ZTIPKDs"]=31472;var __ZTSPKDs=Module["__ZTSPKDs"]=31488;var __ZTIDi=Module["__ZTIDi"]=31496;var __ZTSDi=Module["__ZTSDi"]=31504;var __ZTIPDi=Module["__ZTIPDi"]=31508;var __ZTSPDi=Module["__ZTSPDi"]=31524;var __ZTIPKDi=Module["__ZTIPKDi"]=31528;var __ZTSPKDi=Module["__ZTSPKDi"]=31544;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=31552;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=31580;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=31592;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=31628;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=31656;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=31684;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=31696;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=31812;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=31824;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=31904;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=31916;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=31956;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=32012;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=32040;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=32060;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=32176;var __ZTSSt9exception=Module["__ZTSSt9exception"]=32108;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=32124;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=32144;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=32156;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=32188;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=32216;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=32336;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=32572;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=32284;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=32304;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=32316;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=32348;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=32364;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=32384;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=32396;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=32452;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=32504;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=32524;var __ZTISt11range_error=Module["__ZTISt11range_error"]=32544;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=32556;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=32584;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=32604;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=32624;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=32636;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=32656;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=32676;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=32688;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=32708;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=32728;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=32788;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=32812;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=32748;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=32772;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=32800;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=32824;function run(){if(runDependencies>0){dependenciesFulfilled=run;return}preRun();if(runDependencies>0){dependenciesFulfilled=run;return}function doRun(){Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(()=>{setTimeout(()=>Module["setStatus"](""),1);doRun()},1)}else{doRun()}}function preInit(){if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].shift()()}}}preInit();run(); +var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof WorkerGlobalScope!="undefined";var ENVIRONMENT_IS_NODE=typeof process=="object"&&process.versions?.node&&process.type!="renderer";if(ENVIRONMENT_IS_NODE){}var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var _scriptName=typeof document!="undefined"?document.currentScript?.src:undefined;if(typeof __filename!="undefined"){_scriptName=__filename}else if(ENVIRONMENT_IS_WORKER){_scriptName=self.location.href}var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");var nodePath=require("path");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename);return ret};readAsync=async(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename,binary?undefined:"utf8");return ret};if(process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){try{scriptDirectory=new URL(".",_scriptName).href}catch{}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=async url=>{if(isFileURI(url)){return new Promise((resolve,reject)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response);return}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}var response=await fetch(url,{credentials:"same-origin"});if(response.ok){return response.arrayBuffer()}throw new Error(response.status+" : "+response.url)}}}else{}var out=console.log.bind(console);var err=console.error.bind(console);var wasmBinary;var wasmMemory;var ABORT=false;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAP64,HEAPU64,HEAPF64;var runtimeInitialized=false;var isFileURI=filename=>filename.startsWith("file://");function updateMemoryViews(){var b=wasmMemory.buffer;HEAP8=new Int8Array(b);HEAP16=new Int16Array(b);HEAPU8=new Uint8Array(b);HEAPU16=new Uint16Array(b);HEAP32=new Int32Array(b);HEAPU32=new Uint32Array(b);HEAPF32=new Float32Array(b);HEAPF64=new Float64Array(b);HEAP64=new BigInt64Array(b);HEAPU64=new BigUint64Array(b)}function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(onPreRuns)}function initRuntime(){runtimeInitialized=true;wasmExports["v"]()}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(onPostRuns)}var runDependencies=0;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var wasmBinaryFile;function findWasmBinary(){return locateFile("index.wasm")}function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}async function getWasmBinary(binaryFile){if(!wasmBinary){try{var response=await readAsync(binaryFile);return new Uint8Array(response)}catch{}}return getBinarySync(binaryFile)}async function instantiateArrayBuffer(binaryFile,imports){try{var binary=await getWasmBinary(binaryFile);var instance=await WebAssembly.instantiate(binary,imports);return instance}catch(reason){err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)}}async function instantiateAsync(binary,binaryFile,imports){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE){try{var response=fetch(binaryFile,{credentials:"same-origin"});var instantiationResult=await WebAssembly.instantiateStreaming(response,imports);return instantiationResult}catch(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation")}}return instantiateArrayBuffer(binaryFile,imports)}function getWasmImports(){return{a:wasmImports}}async function createWasm(){function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["u"];updateMemoryViews();wasmTable=wasmExports["A"];removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){return receiveInstance(result["instance"])}var info=getWasmImports();if(Module["instantiateWasm"]){return new Promise((resolve,reject)=>{Module["instantiateWasm"](info,(mod,inst)=>{resolve(receiveInstance(mod,inst))})})}wasmBinaryFile??=findWasmBinary();var result=await instantiateAsync(wasmBinary,wasmBinaryFile,info);var exports=receiveInstantiationResult(result);return exports}class ExitStatus{name="ExitStatus";constructor(status){this.message=`Program terminated with exit(${status})`;this.status=status}}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var onPostRuns=[];var addOnPostRun=cb=>onPostRuns.push(cb);var onPreRuns=[];var addOnPreRun=cb=>onPreRuns.push(cb);var noExitRuntime=true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>abort("");var embind_init_charCodes=()=>{var codes=new Array(256);for(var i=0;i<256;++i){codes[i]=String.fromCharCode(i)}embind_charCodes=codes};var embind_charCodes;var readLatin1String=ptr=>{var ret="";var c=ptr;while(HEAPU8[c]){ret+=embind_charCodes[HEAPU8[c++]]}return ret};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};var throwBindingError=message=>{throw new BindingError(message)};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){return sharedRegisterType(rawType,registeredInstance,options)}var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];case 8:return signed?pointer=>HEAP64[pointer>>3]:pointer=>HEAPU64[pointer>>3];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);const isUnsignedType=minRange===0n;let fromWireType=value=>value;if(isUnsignedType){const bitSize=size*8;fromWireType=value=>BigInt.asUintN(bitSize,value);maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>{if(typeof value=="number"){value=BigInt(value)}return value},argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,!isUnsignedType),destructorFunction:null})};var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var init_ClassHandle=()=>{let proto=ClassHandle.prototype;Object.assign(proto,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}});const symbolDispose=Symbol.dispose;if(symbolDispose){proto[symbolDispose]=proto["delete"]}};function ClassHandle(){}var createNamedFunction=(name,func)=>Object.defineProperty(func,"name",{value:name});var registeredPointers={};var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module[name].overloadTable.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var InternalError=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};var throwInternalError=message=>{throw new InternalError(message)};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var embind__requireFunction=(signature,rawFunction,isAsync=false)=>{signature=readLatin1String(signature);function makeDynCaller(){var rtn=getWasmTableEntry(rawFunction);return rtn}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};class UnboundTypeError extends Error{}var getTypeName=type=>{var ptr=___getTypeName(type);var rv=readLatin1String(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(type=>typeDependencies[type]=dependentTypes);function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=readLatin1String(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError(`Use 'new' to construct ${name}`)}if(undefined===registeredClass.constructor_body){throw new BindingError(`${name} has no accessible constructor`)}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex===-1)return signature;return signature.slice(0,argsIndex)};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync,isNonnullReturn)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=readLatin1String(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker,isAsync);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=readLatin1String(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[0,1,,1,null,1,true,1,false,1];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var Emval={toValue:handle=>{if(!handle){throwBindingError(`Cannot use deleted val. handle = ${handle}`)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=readLatin1String(name);registerType(rawType,{name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync,isNonnullReturn)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=readLatin1String(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker,isAsync);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);const isUnsignedType=minRange===0;let fromWireType=value=>value;if(isUnsignedType){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift;maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array,BigInt64Array,BigUint64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=readLatin1String(name);registerType(rawType,{name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=55296&&u<=57343){var u1=str.charCodeAt(++i);u=65536+((u&1023)<<10)|u1&1023}if(u<=127){if(outIdx>=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx=0,maxBytesToRead=NaN)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=readLatin1String(name);var stdStringIsUTF8=true;registerType(rawType,{name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(valueIsOfTypeString){if(stdStringIsUTF8){stringToUTF8(value,ptr,length+1)}else{for(var i=0;i255){_free(base);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}}else{HEAPU8.set(value,ptr)}if(destructors!==null){destructors.push(_free,base)}return base},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var UTF16Decoder=typeof TextDecoder!="undefined"?new TextDecoder("utf-16le"):undefined;var UTF16ToString=(ptr,maxBytesToRead)=>{var idx=ptr>>1;var maxIdx=idx+maxBytesToRead/2;var endIdx=idx;while(!(endIdx>=maxIdx)&&HEAPU16[endIdx])++endIdx;if(endIdx-idx>16&&UTF16Decoder)return UTF16Decoder.decode(HEAPU16.subarray(idx,endIdx));var str="";for(var i=idx;!(i>=maxIdx);++i){var codeUnit=HEAPU16[i];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var i=0;var str="";while(!(i>=maxBytesToRead/4)){var utf32=HEAP32[ptr+i*4>>2];if(utf32==0)break;++i;if(utf32>=65536){var ch=utf32-65536;str+=String.fromCharCode(55296|ch>>10,56320|ch&1023)}else{str+=String.fromCharCode(utf32)}}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i=55296&&codeUnit<=57343){var trailSurrogate=str.charCodeAt(++i);codeUnit=65536+((codeUnit&1023)<<10)|trailSurrogate&1023}HEAP32[outPtr>>2]=codeUnit;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i=55296&&codeUnit<=57343)++i;len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=readLatin1String(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=readLatin1String(name);registerType(rawType,{isVoid:true,name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};embind_init_charCodes();init_ClassHandle();init_RegisteredPointer();{if(Module["noExitRuntime"])noExitRuntime=Module["noExitRuntime"];if(Module["print"])out=Module["print"];if(Module["printErr"])err=Module["printErr"];if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"]}var wasmImports={f:___cxa_throw,p:__abort_js,k:__embind_register_bigint,m:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,r:__embind_register_emval,j:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,s:__embind_register_std_string,g:__embind_register_std_wstring,n:__embind_register_void,o:__emval_take_value,t:_emscripten_date_now,q:_emscripten_resize_heap,i:_fd_write};var wasmExports;createWasm();var ___wasm_call_ctors=()=>(___wasm_call_ctors=wasmExports["v"])();var _param_get=Module["_param_get"]=(a0,a1)=>(_param_get=Module["_param_get"]=wasmExports["w"])(a0,a1);var _param_set_used=Module["_param_set_used"]=a0=>(_param_set_used=Module["_param_set_used"]=wasmExports["x"])(a0);var __Znwm=Module["__Znwm"]=a0=>(__Znwm=Module["__Znwm"]=wasmExports["y"])(a0);var __ZdlPvm=Module["__ZdlPvm"]=(a0,a1)=>(__ZdlPvm=Module["__ZdlPvm"]=wasmExports["z"])(a0,a1);var _malloc=a0=>(_malloc=wasmExports["B"])(a0);var __ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=a0=>(__ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=wasmExports["C"])(a0);var ___cxa_allocate_exception=Module["___cxa_allocate_exception"]=a0=>(___cxa_allocate_exception=Module["___cxa_allocate_exception"]=wasmExports["D"])(a0);var __ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=a0=>(__ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=wasmExports["E"])(a0);var __ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=a0=>(__ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=wasmExports["F"])(a0);var __ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=a0=>(__ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=wasmExports["G"])(a0);var ___cxa_pure_virtual=Module["___cxa_pure_virtual"]=()=>(___cxa_pure_virtual=Module["___cxa_pure_virtual"]=wasmExports["H"])();var ___getTypeName=a0=>(___getTypeName=wasmExports["I"])(a0);var __ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=a0=>(__ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=wasmExports["J"])(a0);var __emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=(a0,a1,a2)=>(__emscripten_memcpy_bulkmem=Module["__emscripten_memcpy_bulkmem"]=wasmExports["K"])(a0,a1,a2);var _emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=()=>(_emscripten_stack_get_end=Module["_emscripten_stack_get_end"]=wasmExports["L"])();var _emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=()=>(_emscripten_stack_get_base=Module["_emscripten_stack_get_base"]=wasmExports["M"])();var _free=a0=>(_free=wasmExports["N"])(a0);var _emscripten_stack_init=Module["_emscripten_stack_init"]=()=>(_emscripten_stack_init=Module["_emscripten_stack_init"]=wasmExports["O"])();var _emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=(a0,a1)=>(_emscripten_stack_set_limits=Module["_emscripten_stack_set_limits"]=wasmExports["P"])(a0,a1);var _emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=()=>(_emscripten_stack_get_free=Module["_emscripten_stack_get_free"]=wasmExports["Q"])();var __ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=()=>(__ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=wasmExports["R"])();var __Znam=Module["__Znam"]=a0=>(__Znam=Module["__Znam"]=wasmExports["S"])(a0);var __ZdlPv=Module["__ZdlPv"]=a0=>(__ZdlPv=Module["__ZdlPv"]=wasmExports["T"])(a0);var __ZdaPv=Module["__ZdaPv"]=a0=>(__ZdaPv=Module["__ZdaPv"]=wasmExports["U"])(a0);var __ZdaPvm=Module["__ZdaPvm"]=(a0,a1)=>(__ZdaPvm=Module["__ZdaPvm"]=wasmExports["V"])(a0,a1);var __ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=(a0,a1)=>(__ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=wasmExports["W"])(a0,a1);var __ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=(a0,a1)=>(__ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=wasmExports["X"])(a0,a1);var __ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=(a0,a1)=>(__ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=wasmExports["Y"])(a0,a1);var __ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=wasmExports["Z"])(a0,a1,a2);var __ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=(a0,a1)=>(__ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=wasmExports["_"])(a0,a1);var __ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=wasmExports["$"])(a0,a1,a2);var __ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=a0=>(__ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=wasmExports["aa"])(a0);var __ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=a0=>(__ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=wasmExports["ba"])(a0);var __ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=a0=>(__ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=wasmExports["ca"])(a0);var __ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=()=>(__ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=wasmExports["da"])();var __ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=()=>(__ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=wasmExports["ea"])();var __ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=()=>(__ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=wasmExports["fa"])();var __ZSt9terminatev=Module["__ZSt9terminatev"]=()=>(__ZSt9terminatev=Module["__ZSt9terminatev"]=wasmExports["ga"])();var ___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=()=>(___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=wasmExports["ha"])();var ___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=a0=>(___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=wasmExports["ia"])(a0);var ___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=()=>(___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=wasmExports["ja"])();var ___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=()=>(___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=wasmExports["ka"])();var ___cxa_free_exception=Module["___cxa_free_exception"]=a0=>(___cxa_free_exception=Module["___cxa_free_exception"]=wasmExports["la"])(a0);var ___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=(a0,a1,a2)=>(___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=wasmExports["ma"])(a0,a1,a2);var ___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=()=>(___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=wasmExports["na"])();var ___dynamic_cast=Module["___dynamic_cast"]=(a0,a1,a2,a3)=>(___dynamic_cast=Module["___dynamic_cast"]=wasmExports["oa"])(a0,a1,a2,a3);var __ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=a0=>(__ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=wasmExports["pa"])(a0);var __ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=a0=>(__ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=wasmExports["qa"])(a0);var __ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=a0=>(__ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=wasmExports["ra"])(a0);var __ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=a0=>(__ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=wasmExports["sa"])(a0);var __ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=a0=>(__ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=wasmExports["ta"])(a0);var __ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=a0=>(__ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=wasmExports["ua"])(a0);var __ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=a0=>(__ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=wasmExports["va"])(a0);var __ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=a0=>(__ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=wasmExports["wa"])(a0);var __ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=a0=>(__ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=wasmExports["xa"])(a0);var __ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=a0=>(__ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=wasmExports["ya"])(a0);var __ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=a0=>(__ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=wasmExports["za"])(a0);var __ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=a0=>(__ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=wasmExports["Aa"])(a0);var __ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=a0=>(__ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=wasmExports["Ba"])(a0);var __ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=a0=>(__ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=wasmExports["Ca"])(a0);var __ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=a0=>(__ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=wasmExports["Da"])(a0);var __ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=a0=>(__ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=wasmExports["Ea"])(a0);var __ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=a0=>(__ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=wasmExports["Fa"])(a0);var __ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=a0=>(__ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=wasmExports["Ga"])(a0);var __ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=a0=>(__ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=wasmExports["Ha"])(a0);var __ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=a0=>(__ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=wasmExports["Ia"])(a0);var __ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=a0=>(__ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=wasmExports["Ja"])(a0);var __ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=a0=>(__ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=wasmExports["Ka"])(a0);var __ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=a0=>(__ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=wasmExports["La"])(a0);var __ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=a0=>(__ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=wasmExports["Ma"])(a0);var __ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=a0=>(__ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=wasmExports["Na"])(a0);var __ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=a0=>(__ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=wasmExports["Oa"])(a0);var __ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=a0=>(__ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=wasmExports["Pa"])(a0);var __ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=a0=>(__ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=wasmExports["Qa"])(a0);var __ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=a0=>(__ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=wasmExports["Ra"])(a0);var __ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=a0=>(__ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=wasmExports["Sa"])(a0);var __ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=a0=>(__ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=wasmExports["Ta"])(a0);var __ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=a0=>(__ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=wasmExports["Ua"])(a0);var __ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=a0=>(__ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=wasmExports["Va"])(a0);var __ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=a0=>(__ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=wasmExports["Wa"])(a0);var __ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=a0=>(__ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=wasmExports["Xa"])(a0);var __ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=a0=>(__ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=wasmExports["Ya"])(a0);var __ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=a0=>(__ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=wasmExports["Za"])(a0);var __ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=a0=>(__ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=wasmExports["_a"])(a0);var __ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=a0=>(__ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=wasmExports["$a"])(a0);var __ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=a0=>(__ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=wasmExports["ab"])(a0);var __ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=a0=>(__ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=wasmExports["bb"])(a0);var __ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=a0=>(__ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=wasmExports["cb"])(a0);var __ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=a0=>(__ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=wasmExports["db"])(a0);var __ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=a0=>(__ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=wasmExports["eb"])(a0);var __ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=a0=>(__ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=wasmExports["fb"])(a0);var __ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=a0=>(__ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=wasmExports["gb"])(a0);var __ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=a0=>(__ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=wasmExports["hb"])(a0);var __ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=a0=>(__ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=wasmExports["ib"])(a0);var __ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=a0=>(__ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=wasmExports["jb"])(a0);var __ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=a0=>(__ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=wasmExports["kb"])(a0);var __ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=a0=>(__ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=wasmExports["lb"])(a0);var __ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=a0=>(__ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=wasmExports["mb"])(a0);var __ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=a0=>(__ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=wasmExports["nb"])(a0);var __ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=a0=>(__ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=wasmExports["ob"])(a0);var __ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=a0=>(__ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=wasmExports["pb"])(a0);var __ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=a0=>(__ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=wasmExports["qb"])(a0);var __ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=a0=>(__ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=wasmExports["rb"])(a0);var __ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=a0=>(__ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=wasmExports["sb"])(a0);var __ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=a0=>(__ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=wasmExports["tb"])(a0);var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=47416;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=47400;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=47392;var __ZTIb=Module["__ZTIb"]=30276;var __ZTIh=Module["__ZTIh"]=30432;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47564;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47548;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47496;var __ZTISt12length_error=Module["__ZTISt12length_error"]=32376;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=32356;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=32140;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=47484;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=32428;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=32408;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=31708;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=31800;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=31668;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28016;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=31920;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28035;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28055;var __ZTIi=Module["__ZTIi"]=30640;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28104;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28171;var __ZTIv=Module["__ZTIv"]=30168;var __ZTIf=Module["__ZTIf"]=31112;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28269;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28356;var __ZTIm=Module["__ZTIm"]=30796;var __ZTIN10emscripten3valE=Module["__ZTIN10emscripten3valE"]=47636;var __ZTSN10emscripten3valE=Module["__ZTSN10emscripten3valE"]=28459;var __ZTIc=Module["__ZTIc"]=30380;var __ZTIa=Module["__ZTIa"]=30484;var __ZTIs=Module["__ZTIs"]=30536;var __ZTIt=Module["__ZTIt"]=30588;var __ZTIj=Module["__ZTIj"]=30692;var __ZTIl=Module["__ZTIl"]=30744;var __ZTIx=Module["__ZTIx"]=30848;var __ZTIy=Module["__ZTIy"]=30900;var __ZTId=Module["__ZTId"]=31164;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28516;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28588;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28664;var __ZTIN10emscripten11memory_viewIcEE=Module["__ZTIN10emscripten11memory_viewIcEE"]=28740;var __ZTIN10emscripten11memory_viewIaEE=Module["__ZTIN10emscripten11memory_viewIaEE"]=28780;var __ZTIN10emscripten11memory_viewIhEE=Module["__ZTIN10emscripten11memory_viewIhEE"]=28820;var __ZTIN10emscripten11memory_viewIsEE=Module["__ZTIN10emscripten11memory_viewIsEE"]=28860;var __ZTIN10emscripten11memory_viewItEE=Module["__ZTIN10emscripten11memory_viewItEE"]=28900;var __ZTIN10emscripten11memory_viewIiEE=Module["__ZTIN10emscripten11memory_viewIiEE"]=28940;var __ZTIN10emscripten11memory_viewIjEE=Module["__ZTIN10emscripten11memory_viewIjEE"]=28980;var __ZTIN10emscripten11memory_viewIlEE=Module["__ZTIN10emscripten11memory_viewIlEE"]=29020;var __ZTIN10emscripten11memory_viewImEE=Module["__ZTIN10emscripten11memory_viewImEE"]=29060;var __ZTIN10emscripten11memory_viewIxEE=Module["__ZTIN10emscripten11memory_viewIxEE"]=29100;var __ZTIN10emscripten11memory_viewIyEE=Module["__ZTIN10emscripten11memory_viewIyEE"]=29140;var __ZTIN10emscripten11memory_viewIfEE=Module["__ZTIN10emscripten11memory_viewIfEE"]=29180;var __ZTIN10emscripten11memory_viewIdEE=Module["__ZTIN10emscripten11memory_viewIdEE"]=29220;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28524;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28596;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28672;var __ZTSN10emscripten11memory_viewIcEE=Module["__ZTSN10emscripten11memory_viewIcEE"]=28748;var __ZTSN10emscripten11memory_viewIaEE=Module["__ZTSN10emscripten11memory_viewIaEE"]=28788;var __ZTSN10emscripten11memory_viewIhEE=Module["__ZTSN10emscripten11memory_viewIhEE"]=28828;var __ZTSN10emscripten11memory_viewIsEE=Module["__ZTSN10emscripten11memory_viewIsEE"]=28868;var __ZTSN10emscripten11memory_viewItEE=Module["__ZTSN10emscripten11memory_viewItEE"]=28908;var __ZTSN10emscripten11memory_viewIiEE=Module["__ZTSN10emscripten11memory_viewIiEE"]=28948;var __ZTSN10emscripten11memory_viewIjEE=Module["__ZTSN10emscripten11memory_viewIjEE"]=28988;var __ZTSN10emscripten11memory_viewIlEE=Module["__ZTSN10emscripten11memory_viewIlEE"]=29028;var __ZTSN10emscripten11memory_viewImEE=Module["__ZTSN10emscripten11memory_viewImEE"]=29068;var __ZTSN10emscripten11memory_viewIxEE=Module["__ZTSN10emscripten11memory_viewIxEE"]=29108;var __ZTSN10emscripten11memory_viewIyEE=Module["__ZTSN10emscripten11memory_viewIyEE"]=29148;var __ZTSN10emscripten11memory_viewIfEE=Module["__ZTSN10emscripten11memory_viewIfEE"]=29188;var __ZTSN10emscripten11memory_viewIdEE=Module["__ZTSN10emscripten11memory_viewIdEE"]=29228;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=32180;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32016;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=32200;var __ZTISt9exception=Module["__ZTISt9exception"]=32036;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=47864;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=47860;var ___cxa_new_handler=Module["___cxa_new_handler"]=50108;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=29744;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=29792;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=29840;var __ZTIDn=Module["__ZTIDn"]=30220;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=29888;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=29936;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=29988;var __ZTISt9type_info=Module["__ZTISt9type_info"]=32700;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=29756;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=29804;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=29852;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=29900;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=29948;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=3e4;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=30060;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=30088;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=30116;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=30128;var __ZTSv=Module["__ZTSv"]=30176;var __ZTIPv=Module["__ZTIPv"]=30180;var __ZTSPv=Module["__ZTSPv"]=30196;var __ZTIPKv=Module["__ZTIPKv"]=30200;var __ZTSPKv=Module["__ZTSPKv"]=30216;var __ZTSDn=Module["__ZTSDn"]=30228;var __ZTIPDn=Module["__ZTIPDn"]=30232;var __ZTSPDn=Module["__ZTSPDn"]=30248;var __ZTIPKDn=Module["__ZTIPKDn"]=30252;var __ZTSPKDn=Module["__ZTSPKDn"]=30268;var __ZTSb=Module["__ZTSb"]=30284;var __ZTIPb=Module["__ZTIPb"]=30288;var __ZTSPb=Module["__ZTSPb"]=30304;var __ZTIPKb=Module["__ZTIPKb"]=30308;var __ZTSPKb=Module["__ZTSPKb"]=30324;var __ZTIw=Module["__ZTIw"]=30328;var __ZTSw=Module["__ZTSw"]=30336;var __ZTIPw=Module["__ZTIPw"]=30340;var __ZTSPw=Module["__ZTSPw"]=30356;var __ZTIPKw=Module["__ZTIPKw"]=30360;var __ZTSPKw=Module["__ZTSPKw"]=30376;var __ZTSc=Module["__ZTSc"]=30388;var __ZTIPc=Module["__ZTIPc"]=30392;var __ZTSPc=Module["__ZTSPc"]=30408;var __ZTIPKc=Module["__ZTIPKc"]=30412;var __ZTSPKc=Module["__ZTSPKc"]=30428;var __ZTSh=Module["__ZTSh"]=30440;var __ZTIPh=Module["__ZTIPh"]=30444;var __ZTSPh=Module["__ZTSPh"]=30460;var __ZTIPKh=Module["__ZTIPKh"]=30464;var __ZTSPKh=Module["__ZTSPKh"]=30480;var __ZTSa=Module["__ZTSa"]=30492;var __ZTIPa=Module["__ZTIPa"]=30496;var __ZTSPa=Module["__ZTSPa"]=30512;var __ZTIPKa=Module["__ZTIPKa"]=30516;var __ZTSPKa=Module["__ZTSPKa"]=30532;var __ZTSs=Module["__ZTSs"]=30544;var __ZTIPs=Module["__ZTIPs"]=30548;var __ZTSPs=Module["__ZTSPs"]=30564;var __ZTIPKs=Module["__ZTIPKs"]=30568;var __ZTSPKs=Module["__ZTSPKs"]=30584;var __ZTSt=Module["__ZTSt"]=30596;var __ZTIPt=Module["__ZTIPt"]=30600;var __ZTSPt=Module["__ZTSPt"]=30616;var __ZTIPKt=Module["__ZTIPKt"]=30620;var __ZTSPKt=Module["__ZTSPKt"]=30636;var __ZTSi=Module["__ZTSi"]=30648;var __ZTIPi=Module["__ZTIPi"]=30652;var __ZTSPi=Module["__ZTSPi"]=30668;var __ZTIPKi=Module["__ZTIPKi"]=30672;var __ZTSPKi=Module["__ZTSPKi"]=30688;var __ZTSj=Module["__ZTSj"]=30700;var __ZTIPj=Module["__ZTIPj"]=30704;var __ZTSPj=Module["__ZTSPj"]=30720;var __ZTIPKj=Module["__ZTIPKj"]=30724;var __ZTSPKj=Module["__ZTSPKj"]=30740;var __ZTSl=Module["__ZTSl"]=30752;var __ZTIPl=Module["__ZTIPl"]=30756;var __ZTSPl=Module["__ZTSPl"]=30772;var __ZTIPKl=Module["__ZTIPKl"]=30776;var __ZTSPKl=Module["__ZTSPKl"]=30792;var __ZTSm=Module["__ZTSm"]=30804;var __ZTIPm=Module["__ZTIPm"]=30808;var __ZTSPm=Module["__ZTSPm"]=30824;var __ZTIPKm=Module["__ZTIPKm"]=30828;var __ZTSPKm=Module["__ZTSPKm"]=30844;var __ZTSx=Module["__ZTSx"]=30856;var __ZTIPx=Module["__ZTIPx"]=30860;var __ZTSPx=Module["__ZTSPx"]=30876;var __ZTIPKx=Module["__ZTIPKx"]=30880;var __ZTSPKx=Module["__ZTSPKx"]=30896;var __ZTSy=Module["__ZTSy"]=30908;var __ZTIPy=Module["__ZTIPy"]=30912;var __ZTSPy=Module["__ZTSPy"]=30928;var __ZTIPKy=Module["__ZTIPKy"]=30932;var __ZTSPKy=Module["__ZTSPKy"]=30948;var __ZTIn=Module["__ZTIn"]=30952;var __ZTSn=Module["__ZTSn"]=30960;var __ZTIPn=Module["__ZTIPn"]=30964;var __ZTSPn=Module["__ZTSPn"]=30980;var __ZTIPKn=Module["__ZTIPKn"]=30984;var __ZTSPKn=Module["__ZTSPKn"]=31e3;var __ZTIo=Module["__ZTIo"]=31004;var __ZTSo=Module["__ZTSo"]=31012;var __ZTIPo=Module["__ZTIPo"]=31016;var __ZTSPo=Module["__ZTSPo"]=31032;var __ZTIPKo=Module["__ZTIPKo"]=31036;var __ZTSPKo=Module["__ZTSPKo"]=31052;var __ZTIDh=Module["__ZTIDh"]=31056;var __ZTSDh=Module["__ZTSDh"]=31064;var __ZTIPDh=Module["__ZTIPDh"]=31068;var __ZTSPDh=Module["__ZTSPDh"]=31084;var __ZTIPKDh=Module["__ZTIPKDh"]=31088;var __ZTSPKDh=Module["__ZTSPKDh"]=31104;var __ZTSf=Module["__ZTSf"]=31120;var __ZTIPf=Module["__ZTIPf"]=31124;var __ZTSPf=Module["__ZTSPf"]=31140;var __ZTIPKf=Module["__ZTIPKf"]=31144;var __ZTSPKf=Module["__ZTSPKf"]=31160;var __ZTSd=Module["__ZTSd"]=31172;var __ZTIPd=Module["__ZTIPd"]=31176;var __ZTSPd=Module["__ZTSPd"]=31192;var __ZTIPKd=Module["__ZTIPKd"]=31196;var __ZTSPKd=Module["__ZTSPKd"]=31212;var __ZTIe=Module["__ZTIe"]=31216;var __ZTSe=Module["__ZTSe"]=31224;var __ZTIPe=Module["__ZTIPe"]=31228;var __ZTSPe=Module["__ZTSPe"]=31244;var __ZTIPKe=Module["__ZTIPKe"]=31248;var __ZTSPKe=Module["__ZTSPKe"]=31264;var __ZTIg=Module["__ZTIg"]=31268;var __ZTSg=Module["__ZTSg"]=31276;var __ZTIPg=Module["__ZTIPg"]=31280;var __ZTSPg=Module["__ZTSPg"]=31296;var __ZTIPKg=Module["__ZTIPKg"]=31300;var __ZTSPKg=Module["__ZTSPKg"]=31316;var __ZTIDu=Module["__ZTIDu"]=31320;var __ZTSDu=Module["__ZTSDu"]=31328;var __ZTIPDu=Module["__ZTIPDu"]=31332;var __ZTSPDu=Module["__ZTSPDu"]=31348;var __ZTIPKDu=Module["__ZTIPKDu"]=31352;var __ZTSPKDu=Module["__ZTSPKDu"]=31368;var __ZTIDs=Module["__ZTIDs"]=31376;var __ZTSDs=Module["__ZTSDs"]=31384;var __ZTIPDs=Module["__ZTIPDs"]=31388;var __ZTSPDs=Module["__ZTSPDs"]=31404;var __ZTIPKDs=Module["__ZTIPKDs"]=31408;var __ZTSPKDs=Module["__ZTSPKDs"]=31424;var __ZTIDi=Module["__ZTIDi"]=31432;var __ZTSDi=Module["__ZTSDi"]=31440;var __ZTIPDi=Module["__ZTIPDi"]=31444;var __ZTSPDi=Module["__ZTSPDi"]=31460;var __ZTIPKDi=Module["__ZTIPKDi"]=31464;var __ZTSPKDi=Module["__ZTSPKDi"]=31480;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=31488;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=31516;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=31528;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=31564;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=31592;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=31620;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=31632;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=31748;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=31760;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=31840;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=31852;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=31892;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=31948;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=31976;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=31996;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=32112;var __ZTSSt9exception=Module["__ZTSSt9exception"]=32044;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=32060;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=32080;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=32092;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=32124;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=32152;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=32272;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=32508;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=32220;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=32240;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=32252;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=32284;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=32300;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=32320;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=32332;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=32388;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=32440;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=32460;var __ZTISt11range_error=Module["__ZTISt11range_error"]=32480;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=32492;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=32520;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=32540;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=32560;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=32572;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=32592;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=32612;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=32624;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=32644;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=32664;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=32724;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=32748;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=32684;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=32708;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=32736;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=32760;function run(){if(runDependencies>0){dependenciesFulfilled=run;return}preRun();if(runDependencies>0){dependenciesFulfilled=run;return}function doRun(){Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(()=>{setTimeout(()=>Module["setStatus"](""),1);doRun()},1)}else{doRun()}}function preInit(){if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].shift()()}}}preInit();run(); diff --git a/docs/public/config/failsafe/index.wasm b/docs/public/config/failsafe/index.wasm index decc623efa0ca9bc62eeabb4a58a2085dd9eeb61..b9b4fa1a6c8facd6d789f17a7a24dcedee46ab84 100644 GIT binary patch delta 26334 zcma)l30zgx_W#=FUJ$sTS4B}AI9%r$hj4^@HqL^x=2#ACD$a(crk-n9P>*`#A&-^S zt!HIDEnZk^X;9gV`eRvXSz2LPnOTw|qEY@oYwdLqdGz`G_Zxl`rJLw+o-;NsiLgcKKi5h68W@v`YC6S?S zdXh&WQ3F|3u1R_*E7ww>uM1=jNyWSHLDv#Bh!h^=cGMtBc%+H8y|+Y(SPwqwplh;N zq+16&=kRZ2^iG~`)qEBTXt+{UUSWY%$Z+M0f9Xzp&-)a$>q#ew%riadMek#+| zQG=0DLI>TQ9uL?W&5)&;)@PyZLQ67TvLw^`EA$ENSf=$vy;QyGK3BRA0qd?|ZbR2} zk*I+#qJ%t}>5@k?t{f|w{)4^-C5AW!}pA>$q25v-E2ksFO*#nMc zx^x8Az@vk_E=Icz9pu`TvOLq39ZTG1!=46BW+v#9!Ps%(aMR|qyf=}HR#gj=;uNYkw-8sdwp#g`;%xhUS)OV)>YJ0pq}-Z-(t%Jp_b6ouYS zNIU1%#f}0`!=^&KZuuG|h*t|HHtHd|W_}^`5Cjq;gRbE-7HI3S4LvJo(T{JYaM4 zDhi&D?xKZmuh8W7ih?hiKCi_b{DWpFNO!t-ybhjd&_N#k!^&$uSu4r3erZ0i6%MZt zbRnxUUFl@LqZa0)*;|rn4USF2$^S@f7bU3aP%Q{G1;31)(w1h5;OUA}M#s4lMsvmG z%#}$k26njtY}o$b&D$ZOE$oY0-q~ z)=zQK@!46fZUEAa{ifoQM)8EguiKD0R!e=Lwkyk;rgx2ED+syjeru~fTicywmFvAi z(0{hoB|f=t)%`B^pu1HBk^%Cq1NKEAORav-4KFV85{&O?syOKb2^f|~x4>n83Og@R z1CNAwkhxhd-Hk2J$x>vA>)b?2S*8nnsiQ{Q!FKKt7e*IXhEL5qT~L_u;at##3~X_w z)4aeCneK}KsSl3=k35lSjrTRz&SY9ke0u2FOqbl7Wo`9!L(1E}=uj19t&_g?Ns7r{ zBVB|tGE^0A52D9dtfkg$iLT);5F&G|(OjIlWD!trrK|5o34p@ zS*}hR^wqq&z?RcjB>*|Dv4uI-3; z3Z;U!A`YY>7;`gxG#N0EPHeZ&r?wLx;5-7F%kaN*xpRoyBa1Vw8STf7=4_h2cPQkzW3>4-;-UFqH zJ`Pl981Tf(D3Jf5XB~z|fi5u2tdRGf5W0|MknW9^2P-s+Ef}myZZh&g4I^*YHZq%y zl#-DWvxb#ZH(B|zhLulhTN%ezj*^vAHH@6U$;i(&jGV4*#E|!%FtI_#VsA7mR=20> zCL>pC82P=nkpxDPfPGR`!$!^(m0YNfec;NCj@?Yps$*wS&+2SMM-GL4wbD#W z3~1v-l9hv^t>gh&xWT_afKzTa<;|G7x+$I3T{lwhUIXuKQ9I?PorX7qj|Vm%_*ImVtgn;8tigk-Q|gt2IHe|B6pj8D*ZibxY{P}5rYh8{4BGN0Q>gEd ze3uG)TFo$z>5?nMSI-H1Zzg}N<^5sh_`lJLGYgg&p&{a*1$PboQ;1-}%HiJ#t>k#Y z_>q%c$laB;M>9|SB4m!&8zm2)7xIfpDI|C!Y^sUi1Id)XTA~AEe}O`L*?#oh1BHt_*nTZQZM3TUb*IN zC=Zunvv$5Eyh5I*=b!00@3fFYzC+IkPouv1`x_{9=CqJ5nfoR_=X{6O_S5s;?}QAI z$LaYL(H|~EnJwQVeK$QT2X7ukx^nP1Ju3%)(zCLElAe|QOaifYA~`sH2$gq#FJzc3 zqUU4Z3mGn-qUWmbg$$K{5Qv>;gsdmOL&u)hAj7;pb@0yifjnQu5x26+GRJpG3|`da zu8W%7e-Vdo_epH*D<`pA)W7@c%m17d(&hC?6cw`gq9%7+rQ_q8Vf_&=&8NL5g$&h! zp7&cZ6BP6QhIKHpC{>Gn49f&4GU4SW{-jEWb+>adzRNr63C7jp|U zH`k|yiD1KYpy&P8A!eRvP>0zHW(Mjq+helw`Cg+sG#4`STKzhh&oJ}Bx_o}c%!_rI zZG5Zp`9)pKG-ejoh4wyXo~;YeTg-g1EoCVxC7WK$W# z?zb z*F(ZWp5hj@mT}&CGK{7_;9V9-9Wz}tc`8!6Wa%YM?yycxjcv{j_>=W4uzVioo<*9^P!VUNbh)1>gw*`Eo-~Q#@H#C#b>eDqJG-h45O;9IM0hfsLzW zZzQwU>ggjqHRx9H^j02qOXG9ltxehVet4VHdBzX74UIGV>J?QEmBP!Tq-n5V*y^Gb>x*)n(e8fsP{$9c`WCM@OH{ zxxKmLNO$X@I^KrCh!)sOFIuDK8ev6Q_1bE(D9hS9ca2t@X+_+z4edUA$5vOfs*9TL zl40rI`grWqJZdoaUbE5`%x}rf!pkUaxZ7|UdT0;fm97j~y1C%Uf`17uucBbpqBlcD zc0u#dluxqE@Bh!OJbrhb3ycj`iICqxEvK zKBT7g@|&y&T*`WRSfUnitOx3{ZuMSEZJociLkrc!GQ6^^-9+mJCH7^tSZSSNE!L5> z(d!&*bYJ>E*8Zu)-d@)sK{+j|%UT`%x<3^AHL7OI_glvLCcgcliCVtkQOd8&nsxVj z!uH~N2OC|^{tvcalvt~K9I@Owt&j=cExf>X%X|&j>8$EtS`?UK9Wa|Yi_%%;-WLM? zl-nz<$xl7sY&(&pNX6CtM5U(J8vr1Kl~&`Y<0JF0Xq{Xz&TYv2E0*ze%)OX}!?X-mSb8wVxeWV|5%dOl!&Iip>@V>xOc@3Y4_}uIr8hR}QYBG4s>vOnqs&nXD$bP&HvT4i zj)JL`Y7*a|fGky34^*hW@gNxLr5o2RjPk=8D4na9YLrC|$|7Y?-N(3%n8bo-=Epbgqu7QI-lGaEj?3zE5%+ zH%qd~MD3_xkm_9+O4R_V9IN+XG~N{2%^SB+^4txSd>zFouhjtQTuoJj%y&RiaQE%*~b@&@+FqkK?d+WD8!WOv3G9dZngE=;0gtx*$^XAdkFZh|I6lSXK{D z(Xu!A!sW3_t+NJ$p>4*$SI_1E)yW3^5B zT=*(o8yY3#h|77I^ps9qg_TV(f zP(lkqeV1evy*|LCH`Pu!l-sXpQlL=Y6;0CUY~?5>a~*vr%2x+@neAw8akTDrv;vNn zvwc)m|HEi2#JQNNo=w>!tgsHv(5Nj)cG>=@ zyXd);o;7+tLC^HMR%TySU*5^{VP1UoT>Tl6P~D)#({~xV;QJ8k^!}E&bGJbC4T;== zc<7FV(q321D-xHwBJs%b|C5VybTOu;3%Vwe!P+ir+>^MR+&jx%XDh7t4s^ZAWR@ET zb7yUnS#C8Pp_b&ovhs@tUhjq3S99dVN8$F8fE`9{;W$^xh65Bv?N18;QgTC<%G z5UAa?K|SE6^!?WpR>L==odY%xkJbCluCr>|xK1eYYumW)qU2t|qU7Eq_lMTmuv#O& zKh$bi*y5(n+aHRZx3{*B8n-zvC*gnSZ<^lW;LYRl5H)>&ZIchV=}@3xt3!eO^>4=G znS(cv$FI~A2d`SE4?5#P=LL_v@HZA(9J(3Q1+q|78`K3?BAyu(C_Xb3{f)^-4|N?~ zb9jo#{wgaHLYf^-AA+ISZzf2 zx$zjI4B|1yBdxzNSXK*>MFvk?wGxUPMCyF=L)|U178c!%=m%=jsoIEsa3yM9Mx;(f zoBsw;Y0=Gnw3!f@|ETK%cmkT+?J{a&b+Q zr|3g!OkF(>oY$Iw41{?eDfs^F3!MtS`(>Lb$o{on!-A*(Y7%0<;}R|R{p1pldiQOP z7Tet6a^!@G_>y`d+LL55-4V zVSkLgKHWt(;-%RScNeWA?ie~0NH+uPZHTo)u@*Y4!}d20>%3xRIIL*9dk@iuJPcZC z|FgSj6_M`n=GmJZUJmn?I=sF1M-J~4^VT^$x7|8{ZFXHnHpAy34}a`s31YB##(p(H zbeM4R2jLNsAb0h1JmpyFI*EQ1w^mO7V|0&4*7W~DrKwib2nRyw;_hiIvHlg{2X0C%uX zG3)F`oja7yDbg`P5mWCVrL$`Q7P3+mE0v@*?>A3N@q9g z5G^%>boSp3u!wa^SSKHK7AYOGl$D5>x`>p{-wlw?O0ZV7=nN{QE2ZeQsuzfsnoc_U zT7V_2(}#7MtpymjMCpuR9ipW!A)QHU!Gxu(w2+n3P-&@B+Q3RgOI=Dz*=rRhoUA)o zCxAL@l}%ea@Og`IxW`$j9aekq_GasQkO%nxf)>VI)EWO!IrSnI8++4kemlt ziD;=Psg_diI)FRb*-qBWM!h?gv;C|`wA4EZ;Nf)u^H}G^I#BEHAS%sMO6OULXsPo^ zsd62_d{&BFuX>^kb>=G_eZA@lqNUC!ov!Nv7O;-NI&Iejj9Z{|CMg|L5mOhC((LsB zLslz+3|5+oN<&stPh_(rqNSpw>WS^B$17(y>*bQ(U8GmUdPGY_Nu_smeP4hfycEu` zVlgQ$BE?EpBw8v;s-Kqj!~H}I#o>w%(;>D>g-8B`F#n1DZ3o757-CAETSWgC^;N&u2W7gZYpP=8`Z&tCJEFP*b!*{u1i zRxMwJD#&lSsTyO?CCe8qy5j~L4CQwepfoy0g|to81``)8TQg_LqIt9CtXi;o>HK9F zf$3*01IF3p=xsqgJ7SP%(R??vQQl$iCwB56(c+d;ZW_*EY#Mq!zezQDVn)xNtL7|Q zFrQ%}FU$mJYd<_lv@jD))hoC^IjV!qYSli=*UVpa=aS`j*JvcnV;$TA9Gw+6bZ%L_ zY~KGU9Wzy=#n8fQ1J0XZ0w#+a0AM5c#6c5a6R2Q<)90{B(u4`;$1bMDF@dSx}eX96-%anU@Gc>&FHNc0N;bOV6y0MG*yycd#0bWiM))=L3~ z1OSW;0Nr@bVA4A?0HC?mR360i9Q%BdXk((FvUIcN*?d=5URRNr&;Y=)8LHej2B1CwtZAp}BYLUwjwxdS4i0DpkNFkh zPfXVV;JXyHR^M+7&>R3Bn5O8P41jz$z}hs$A3X-(@yD7cx9R{;4*&++Unh$g^Il4Q zbvZE()dGcoAzBFdU#_pz1`*DHza`-e_=jP-0s;TM4b)*FcQQcCzEAocNd<5NfIb?a zckcp!Y-fNYC6WH8Cu3QX)B=Y90J=nDJuN9ck*d?7OFzYUk=ymqOy&5&86=pzXQ(o8 zZwFPr$@KvC5(Emp9h80}L)E8FQuX!r5x*-uS zr}RvJ1{+FeLvd_qG#hHlhMr-?QEcck>wU<2Be_0`>mN)}02{NN-{Mrm*07z}V9ze_(n#)5{sq7feq;x_SNj z^{1He0W&HR6jF-~J<0}BxhKBj7If$GUIv`R@-tYz4a>j6axN~Xu>4O`IHQSYg+I89 zwy@v{7VOI9BMkH>2KX7vPhzL)urFp%}kU&MgMF`#ulP1V)g7*S8|vbWe!fDOIH zj;1r9-VEqomNQtc5zBqW4u>%xn13e&n$G;jCL@xJ$j@Dr&49w4F=Rt4*pS7J1~8!Z z4CpSFOJKR5*x?)OurKq=`224UWPt%JaEQma7Xu1mKuqz~q) z)p&dkz@2wKpWJ}TACuSGNkc_UuN|0tLBM~K61af>4NUML;QucNbvlbez`uqsCjRJQ z-#=8e7TNZ5Lq(QoZg(3dhKu(0YAihVp52-VENdk7W4LPq@@ zqrQ((KW)D@QjBeQ9yfLX7>oNW02J9xMv1uQS(rfsz}L+7Gy5rfG_uz+`y*!eVD<+4 zK4dRqb|JIlm_6M-gzV|e&S!Q5X7{r%BRiGZ&oKKsPnV{4w^R`qJBZm^nSFuT<^AnD zQ$_3M-I$-r{BN26sr_WCh!d^tL#ZOh{9q(9s>H*DJ22%2fGPa|Hhd}I;ralcTLE66Ef?TR1K@<) z1)uWbY0W83**FDo^Avyx0QgTEWv5dYRSrnNGT<+v)F)6lk9YWehSJNMfhmTkw|`kj z5=^ddf1M^`diCVY=ZDEkE{s#BjqO$aKXiZhR?2U;k{{zzU%UNi(O&+{QRkxtD*Qb? zPn8GesPfWmRoYw*uK=su_ZtyMT7epmBnlWf;G=Rs89L zRhi1=ATGOc*_z7+TmqNBrzpK*?&ftQCVnPZ4>qseRoMxZM`LFgDt&$BG`!KOCe`?`L)sVh4>J`_NbsV`g#nHp+w_Oa69@ zYV-n{7b6D$#Mb{k8m;O^4^Cxscwm#q5W1wR)W<<%*=SWSq`G00r>XjVY-cLN_)E<< zd*V3JJYw@L)B^Z@TcN;I_%-8sE z@S&P6{+44@HXkCDn50ulP}c8+O-oCDowL86xM?4bR_?~}K)gv^l9u$_7}ZK|s)DtB zi0YapYGC0LwY?31ld7-f=~e(nY8q7V5LS?bpuC+8NAvNhUK29x?`DTg5OMJj-=c69 zsV;_dJ(b^Obcz8uWe=So;>>KC^@g#4rgPAUqv@*4&21E{3+(_x0U(NYU)|`d=Bs}t z@zau@ZH8up#x_C|@Xw0DdcglBqdlR}8vme3XBd5WrnOb_9{&!WDiwq6-zJFmi;5;t zerK%@(251cc zt@x;xixmKwLOVmB!DoG{{trSEH12G#x^)dLti36dl|Q@pB+;#J zt}>ZQoly4n)6||7DKF4;TamJMy3+fW)7PVH-^=zFvi;>`-%LyXy$dR&CAnxmjz}?R zA?2jZWka*n{4IQz*YEc{ie8!=03Q<&fX6xSeS}&Z@c+sK@hG(zAg4dY8NZtc!bCkc z=yH_(!>uCD^bc1v*`|%BBq_3o>WEt@g;^oXs6hdL4s}4#n5X<2FR3_U2ue``{yB7; zk(O+7xoR>%r5!XMFx$mlQ zq{(-%8s)#dR=jrqUtwh6EFi~MW#{1ij zXyvq$2Vvb9fC>AbN*+qH1fWrpk{`fz7uT~ne0sKD%$vabJbH~s16=!c@xaGb6iq%v8J8|!RhgI37vEJvnQYJHpB(p^Qe98UqvOpA z*@_Z7e$#$#n&>N5+Fwr-FK>0(O5X}tj6ej`k7ZK1aE@ph{jqK9a2kDehq z^qe^mS_F;hw9^Iry=h+Rvh56-umhv{fSGGQH$(It`AjdhUbc-+M+lVcH!5+;o=-@Ri!9VAvFe@{4Y&jN*i@KhKNhe2^(<1rP!N6Zq6W zQ0e*Lc}{0?ct#)L6HF-$Rj$mjyWJ+@#D079Z6apTHHNjOfpWK-XOnjv28#yC%NgGJ z?s$&r?O)6j!Q$j-Dh0pwL;M^R8%yJ|=ug%WZE; z9IeN_?|j0L2Jt!gYrdXnG!5W!9PeqWqqp=@2eobL6ayiA@VuS%F0!7F=zCKZ6Mb)r zhtk5mv4a~EqfGuqf@QKlN4~}Oo>`)Uh_jE+5^*C(sq?8}Qp-R-Kq-kX7ty^$(8%Q5 zlyj7mKbHJ0C3EYCjOOF~`_t68d+nszBF^kOQQe%k;Mx0xnvMQlyw|yV<663$bk7hq z09$F@_et4G)5DOrP-_k20G-8({C!hZZ%AI^UD@rYH1N9YB{7%<3PWh%0=~lgskK4l zEH8uqa`w840D!T}{&Tj7F^j0T^tap3R9jOBl_kluRQ!^k&A>SHqyG$rlAx?0^%W^* z0^)A&KgUu1F|OZB$Nhl+RkCXoHRaL2O!{EFM$4ke{{Zd5My&BJF#^Vanen({7(RQ? z91#=Si1*&lsULJ%uFj?@KTNZ~nIl?@c>B*exVsJERmVHb$o?+z z6bX}OvYeMUqff^Ilna13zuGkBq^g%$=h_2Y_XB*xtGz29_y5bW<98aSp#A1t5gy*1 z@`beIW%iM|BF1b;IsyMcTKT&CmL`6{{|C)1fP;KP7D4at0h;j3qsx3l)`QD}**LTS zQ@H$!W+cFm%-6Zx$@~$jOb49_4Y|~~e2wod;~C&00vIT~&MRvZ<#mC=Y;Gif90lzu z%f2>b6J^=!hfGlWh5uvw$Q>f4|7s?WWb*6y3N7&Fkc%FLKa$nwv0Oiv%d=a}6EXcK zGPwhjSF!prRzF85uMJ6Ixuz^P&R&Y@J((QBa*N%dk?C2V)CC1svWDp!sZ6`6QE1 zbK4(b^`}_9g4_Nf%N5$A?-ViSZ%lrN$*;5eLzEdA{;+s8{z+Vq;)pbl>rZkyh08|x z!V_O6^E$bW=lk6}&wt`+{0~)jfgVh-_~q#lj!BR6#{LU$-IYD<`U^yN(`LhWv*AbB z@Vk_U103d^NidKE-f3p=dF2z9`;>Q{FBtd-TrTHQo18hhExF@=M@(z~2Kp9G)Fq-)zc)@n&axRy< zC|Cl##c~f5-3%1A;hU60DJlc(%L>i8+{c%;_p{V8Fj?g4*rQFwS?? zeSlF;xniJj8=tvHsLTVtvb!x39n3X+c6opYJcl#7AV>MDQ29f{`V=)a02$mbP*#? z*^j1+vGHrt0eTmd4<3^aFv?C!nUSu}6z2x3t$(5&vRHIzSjA(poKwXOcG6-I)BHo4 zb1PDw=RVD&%is|y$@bF4BF>zs?*8B&Zqf^sZUCh7rOGPWI02?|ndAq+Wwbm-y)M|- zM`h{Xa(cX$hp<1V(eo43(5>Wa|M!NfdUqw?2*I$IYvCeUwVCrUrGVMOZ3GOKn&A|F}*$0Ew!ne z@DA_l&+;cB4>Ewuv?CO!Br$+5X(|`Xzt~_m1`x#n)-(M@cJu%{s^ILQ9n(XYzKZB3 zz%vYBGXv{52JkgIiev!i+2Ay$XS1V)Oh3*5+)O{ie#Rpmzvc}vfZ5FW zh7V#-GJqdw`vKU@01mRFU)bRPV@Lg%zJTe&nZB0+e9wN~Wj_fE`Q864X84(LhL_hD z+!IY{E^JG=oq8f@Tq7WQ%21vQ8Qc?-cqo?fe(??OJNI(AneCmUhHXpfbqlpWXne#5 z2eHA$Y%rA#&S!(i+0Z&JyRgBx*kC9Fe3tF?W_xqlUJBcr$@WTStFNhH1sgohUB8tL zennj$G}f@e&TMcR8|=>pCptSM+gZTn3GT_)8K{R>)kL0C7fdo-ETh@*U^d)_4d?Qh z7V?-r&0`wL^npxo!Srk%>wP?=HV^4+2JkJoLn7)kxtYLZt11Mksf2c`qg3SOvWk-SmoMuO3n7)x6-Ny6}+0j*Y^d&nQ z#`M)ppUm{VJhWL1;9~+{0xV_#|6xa^?5Kzxbz}NWrVnEJi|ptGJKE2V+A)0+)B7;} zZJrBzxF;yQn^2rGg2&7dFJu`Y%p7%m8LH zfalrKadz|?JMuAoJkxtJ{V8^IgdOc+N3l#F$@ET4e~srtyV>*A-CxLDbsgfTKoT_G zo`mP{HiKqRh66@ly3Ww$GA_sSebeJ~4H59SW%_ZtP7U}QQ)(UXziNkMhz{nxD$nu{ z<=cjxlppFTcTrwiEH_V5?hmWml9UsCL7K-|#;x?(A;4)rz^M>`ExLM#_AQ?TM)C>Z zXU_QdGCf|=O=!v4$6*$DX_CsRf_xqFB-bD0dM?*jb3KHC{Gt+R<2_2W14b#;i~QTU z{xZLXKFAr~KH@h9V~;Xq+}?xoB6EeEv|7ZBTE%HuOa7c~J!i5z`E!uS1a;rhlM?n| z$|owFl1J(2q{~m##~A+O(tc{SXc}KdFYXNEN6t7`^1aAo)7AaUNA~g6Vr;{aG(1H{ zE*%YnMXT&v)`&PWmgnViI#>n#6Bx}q>eXU$e|2Co{!+J-{y*q;Wrci&Q_`hW1`7Y8 zySG5$JobKq7I?rvmD~mV|Djp4Hw8aEUcrAklDU)?BY=KD{W*cXRArD@?|1;{&x`PH zUhvP1YX0J1_TVqdA$`LEAUQN%yc8h&fcmc3vkd6(p&UN`Z4^G^A6uZ^4F^nBaRl(s zNS5-K^k@X@hnFc(Wb}YCh$ZUa4;sZf{{0Kmuq-(M5dDS%f^`Jeg+8%XfYBDouRZ|q zSv`Q?LjVSc0`v$4cq_(L-|y4C&)RGF?P=|`*EzSo zyBKn$JS0Ct)AI8QBDD`R(cJpdIo;fTS?j2QghBG??;8H?sDUR$PF|F(fo5ukW=J2g zWICxPk3zBrvg~(FQl<2FEggC}Kvt7zoC7PmmaIXfaA9jl4WfignyA}-dz5J9!kP}c zCQC$)wJ)SuHd+P=vVyo9Y0wI7D*dR{0U=Db+&;I1PEs?@-`M{0{t!qLAakfzcg0NO51X=F}bX zC^Zd?3YCZb4%M%tTxsayR!;+^^Qf&8Sr7k@PRo_xwmO7&wBe5qKUNDjqN)e?poqM_ zhy4y6fi-mLAg_xdPD2N|e33locjUxrnkfs(md7cD4$`qS*8_`i&I|okgllm;j!m4C zR)mSefy*RR3SH!SG~z4vTS3=>&{KYgJmt5hMOKO9)}*Ke?V;n=15vkVPoJ<}iSpvp zFHyQUZZ(YVg|tD@oshO98flM3cSYL!idI3irVWWUpkb%@hmH$9L>?76?ilO?^o4Pe z!lj4k&{3P1tQ8A++}f(x->qQ})?%Mi!#+1z+l=f@+@w9jeH)@!=#CY~tezgnKgN#f^%QH{Hb#DfS1frQAQBd0y+4%e|z5lTBoGo=3tZ6wW! zRqNFzT{Zs|>r9iTT5!E}xyi7|;Cd~mqvnhY#pV$)-Q#^EfTJpKqg~;}hg#wQyX(JF z@O(@sEi~_nCiAWo9B=l#*1Y-}tx%B89QOzvTrr@7++1yKZ8=6O^jkl*?AI2j*8{qc zWqwBvsqd(Td1&<(`mO%0vT^Z0+NzUc)O4s}gxZWJTa9f`D@E{f#U-QTS_z}I;;`4s z=+^yi#U@k`IEV~)>7l#{J=$QWfpuNeL+|wv z`!T;m9`jpWV*8p~^Kkh(4Y{2v=%|8uj&!q^269`TBi$GD`FuVnK5or(=n*n9M=o3> zPrUTSOCgKV^v*oq#g!Yl;?rFok>hbn(8ax;28%pG4;>N}CM!13P6=@uvP@OObnA!M zn7GOfj?MtmiQ}gHl1Bc7+^^G+)m9t5pSCT}8mA{lu@;0}w!zw>PtmsLSrvNs5VT)u zb&5;tRkp#w7IdfbK(d?+>VRWWzCrDN*9|KUvJ#BzXevMH0SV}qhqT6Re*_0FSp%1Z zIFPDQdJ{cjdT#o z$WT={U5Fliv6fZ4C%T5GK!~ii(&D>_YHMD6l13(D8qjJz=C|I8ud!PipP1~=bKI&y zFU_qB>^arLq(9H03mKM!z5m~V$;-3S+u!4&%>v|Bt=HN&#qIb<$M)8R_JiWcl?pnF z*pY^y&&~DFVn9ba>Xtnob)0wr*AdWKhW}m5w}m)ea?BduE@h2DVNfjSbX&$+6x6Jj46TW)>7&5gsC4>3ALfev45$!-6s*P5fQwU*YZP7_+)7-7AE8rqsOs=U+3 z*puSK7U+1sN_U%Ap_w|kZ}A8n71sn?c=+mqLZY5{DAhc;JTM>%TIt}@ z#lR@g3>j1bTEu`T;Lyhd99J=kc9C*~5q$yOS-dr?Tg+W5`0@y+sf!Q}zcdzg*}4QO zsbfPIQjkJnD^wwyY?vd3tSI=r+itDRiK~3}p-tg=0bVkgupEi zIqn#_>xxEB1HDiopODf-1pBUN=nloAD3GsHU59~DpbKqUDJiU_R(sHtvmQU+KF<6OluR8|iYPwT)la3!*hl%|;TUSXED@npJ zDXXQV`X(h+wSfFuSBK6zbktE@OUI^46?xFOn)1QQ8w0zJ>a~W%%}U&;WK-ph-fXX} zL_S_i$D?(1fYRZPK_N99x{yAR(;i$|1tGm7MM(L1A&*+k`aGqbyKMct&tUDS-x7V} zZRfHmCB{nYy8+Mq_xo}b?xau}qgf|K*t+9J6yCkx`qp)$a5{YWeE6ha%YOf_h&${? z#7*)l;dDw@Gsm+x4S3$MqP9yK1khWNP zLanyv#|X-i>uF$n!u@HVX#Q$zllL2KufJff5gH;sDOjBOhY+O&iw1rpv<+Vtj2Jw| zfvr2UU(w8MWkPOpyQ8H4XCaSAN+H1=Da(Eq@^P0G(r3!+;C9GkzX-XdHX-V7Szz&$m`yCsN@>A>Tw2$m`b~Zig(tDC9@s(kU@KS}w0&zka=M1Ghu& zC>QcD(m|SThdfa(WFYD$Hssp$tB`+3vf?VXqKE5d#jiqMiSj{g*>Tg)}|E{?k$?8(< z)|rFCE#!`~Sl>~E^&@A66!H(ESDZz8bJu=s*#2K39r8a^Km1?Rc8Tg`{}nPsZZ1Tg zt=}U315#A@Ez*CWx-xK?c$9%JsICm`J#a(+V^mlA4-$y7QDk5{J)HYi$S`@0m^Pgg zGF+ad`tEZ=hRT1F(o^SzY#{$xEZoA?4rG|Sn-1L!tiN6D`ZW7SiE%Nn{l=|B@zuuu4b7w!r5{-L#%Ael27u-aUR6 z@{-kjq-uPiQ9X@AxiL^*C7xhX0&W$hCC)s6`k~~pg<1B96skX+= zT?umI#_)Q&a&lDM2poj+denX`WCLBeK|0+{Js{sBzkzkZbrif9R*%-K(F*L>^)>pr zaa}ZROavRI1Jy5C2e|P>!+O+S=0;zAYP*h6Hs5VrkK}A_yc%6k<1^g2u|At$apQ0G zscmwnvU$9|#%yjZst@h`+<3k|KnJ<;#rgnU;l=~?H71Q!fWC3n)6Y3$<4l~g`iQ-vnCpBA#QY{K-nKEyq{twN*K5F?v1{UUngV1*{1IW1%} z*__GGMoS@gU()2iP7B#Wwq)`)JP~$QC~_;=n#q-yG`XunlZ6$U9IgCAo16T@--`t~ zh_-GQF$;O5LiMPfjCD7VVYK`K(_0{Q41Q7NsYvONM=LaW+&XnvTw^3X87-Z%v_g}o zz7aCsD!r>kllC_IKcl54%PTbbU#su9Rzs2f3mlBf3QbmhBV+<*c?hwS_ghC>^iw=; zHvg{4Kfe+3)*F1Tu>vD*>0fWPTRJS+0pJP&`D!CqGrVlp#H^*)mAk~o7sBf_9`2et#OpjS$EuHgyrWoXs^lqJZsB6OSQdzD`MJXsQ1}vTO2LQ zE@`?$hUK`U@g}Ib)MW0sW@XQs(T2N)`6+Fn({LDiXjkEuj$9dBU+~ea=Y;0JQgGj# z{h^|=pv%Im&S*R1l^KP(Dl2(OCro)wTXIXMohOCvbjL{3r8}h?&VNN4fHw<8%8J6Ihv=xqBx}_g-o>2qr?6ygv#ove|5N)V z(wr`_tYoccOrc|vQ|#d6GI*6pJ8f?_*a!&X`^Tk931 zZO95+8>LYHN82Nc?a+#ZBxSU?K5g}k>z+^?*QnY(-(wjon|k(yCTsbEXDPovZPv1t zgzd$ZHa5!F{tvdF6kFR>HrwWUwM||{+8(W8^VQ4txnc`h-N7DSx)Rn|LDqoPq-}W( zo4SA2W!tCNeyU+p7tFeBiEBvP-D^6uQo~DE$hurlDXyb6Ty#gQ%jI56y3*I$y66^I zmutP^+Fip%*Sxx16>Af5UwKT{g*k1f%-3+APOfpL#lErDKC^|rDeYZ;#w6h=Uk49% z%7MZTwZ}jEtIb_d>}wgL`Og%5z4cUB!@qwiLUbV;F2am(@OSIIf3AyuunO<2u2w>r zGOx-S^VIV#@`xlw7Vhqcsx-YpUjVte%4+g-Tx76PyVU{1orVlnTE^4OXYZs-Dkj2| zD)MjcUQ)PwAq8I@fCN_@$QRXh*4Y`vK+1lLMfW)kWOT`GRj4*DobGE6F#x=hh7XSt znt|4fo^Ia$Ay(*$)LeRaI*de!JF7JOd#eLH;fU($)2$*mU(xh1bklP46-y5`w_e%N zDXm~s!;{IC{CJGD~-anUz(N$5n$w z9@m9jWL1Gwd8A~mT<}OMhg*{*LM%2&&K5DqudbLk5-fJ=s0L-J;Mpb5?BaZq)3}+F zRVHgk1%p&CxsakryvKF*Ks#j~${P8A~%CLIBMktl5u1Rwt7JDc;-^C!W)&gngzG^`FY>?#AU7Qee z8nVh{F=Azv$=X65NpkHj)K_aHm0e6MDu~Ll*JRNUi4Bp{X$)~=txTAmSu<-e4(G|H z1Hi@UHgrNPr4TBO$(q3k@f>g=Pc48pPZ9&9Q=le6hcIk>+bd1V_c6dHY5}y2b}^Qx@T z|N7Ka?pTUN6s0K#nGPeJhWs$X-I3fTeNBKVMCd2lV3Dk~kmx!wzSVSm_0l2-2^}@) zsI_R+0Q9h19U#>qum;_=E;>U?d|Rf6%b;??5u@>R7+*-dY{viO|FKh|#TkIVgR-tx7{PZKW9CTr0O#S${sS zH&LgQ$AK@`wah3XH&$8QUTD&)uu9F5(~!kf)k7Ky!0uXiztGwI^Q6!*fvUvg9H_WO zoaT}n?X&8|N{z+J3Q!w7+VWJr1=fR=8VwMBqmf^!>7nuj zR7U{Fos}A%d(gKaV&@kj;)qrHO0yQhpXe+)FJ%4&OeMCV4>orGWJSN)fv+xoUY#wD zSkJzi8H#Ma3)auCPD;ZxB)D5R4L!7@7U_Y^D10qZOHXE82%e9CtrXHjT!`)<4&MbU z@3kab+rif|JxVdz$JgPyqoWoXhtq^F!m;t3bxXd7@nq+Bh(}uRM;5?0%r*+UH^CnZ z{*k{;kdfezR*yIQTHbzZ-y4(W?4q}bu5gg&=uL~OA;|MoYvcfT9JQ!tR}2OuiXRI~ z8mlNpiDIFHJPbPE6-+fLS$Y1lWfpX7wfTxB{dnC0iC4nXby(F5x&4ZDsG!M|&Guyr zJR&p7f%g)p2XMCWGN}u>l|ur2c~|Q(%!MuVWr+(v9^fd?eH&R(1~q)CTwD-imS5J; zB?wtT-AvZPB83ZI*rH9%wpo7JwrR6DU078{TpzR&A*QsimyY&AR@u3-eOF9Em#jfN$e?zw$I%{Z?t4AX_8_-&FR(jG$&C@y3|UEtJ@heBPsVn zuhD4XKyi!Hg{vGr3GD;*p^|C8r>OB%a$BV)1u|`|)Fe&L7ItECvn_9X-x}vD^K2=< zEw$d3^4U`MnNoA4$V&4H8>_g&#(v}DMwVj*aoDG2&0#6e+fwIjssGwirM8qE2-L&@ z@`NpQ%$E8L$DbU=QCrN8a%zGcSz?PFw#DAIjTPHcb^uoszsbF})NWhq4O=STmfCei zvj)G}3)dj-0i4_uKC0&9kjYa}?E*X))Lhvf8r`j;Y_==K=o?YTUYoMp_LlionmkEu zrycHAs6<SZoWDpKsLzn&~TJjp(_ccj||RN<={gI zJ(N;|ljb_m*L<5KRANPoqmMOo!5IZeO2-ekc-9Z-v1&b~Q zF1aVP-j3Co@jandqoUR~4c?wm9K0QMZPd!=IPA;9!++8Bgu#AK5#Rri=-jHE~tx+WV~-EP<-Dg z{tK1=IFLA`_Vg5!%H4HU7CZ1tqBQcA&Id>%jYq(n$9gmn{Da zjT`D{EGLbHbv2edlC|Nik*_e-^=sTxbn{G9lfvSwmQmC+UO`f~n*0A^bu2GR%&t9Z z_tWY)To=*(&SWi#5#bfcC9S_uSY8K_MG8x;3{!Y4Octw2lxRy=v))nwq3QCCh@CX_KeuFwpQ7g(ee|HE`cSw9>11 zbHIkus~R?9_1slWda-hzrQ8FkdNcDm#q6)vhOY(aySKt? zn!JrnT+`$c`nnpUS66wN)*PfS%(cGY+d~&`jT$<9z`)6wLnjXzJaqEFf=_;WTtpLT z^hnu1YjRd*X2Hy#!y75uz)`~|50Q6G9$hf+&*mX6;u|}7XvXA`fprcM>l`_D^sqfo zI>Zz15Uft#b9;<<%(>@O3o$Y#(5T@fqLYLtRBrxG zxMbk=B+*}-4Xj8K2@y|zFI*xLbeo}$Mx`!R9}z|laP?#!IB1evqDi%ulFkXn7+ zMfZj~e-f^zn&M|7XnkSePt@s zmI4f4s%V3j0tlOywG>ch^iqI~`Ko<3%VeWW#(dJVnq`QVg`7Zgo0bCH!?uD;!6ajT z6ud_%+s%SR%esezikAW`W1(YgY%j_zQ!?jShG<#KNTy;bz%-T#Lty|YLz!txrp+?! zl*z=bX(ZHf8Nh57N?{>=8Nl$_N(c?&NDwV+Hpxs}1~8Rn7P8D}l$okz{47JXtf?fk zc^SZBlrdKW>|mih6k4o=_OcMsvKEuj;bj21Z0H2b6rxP7k||>uqGjchOyx3wIV=;o zT#Z6G%FIzRroLSDh=^HpNGNeRKn@ETEYyBE!0;R;G@50ImX$*?Qt@UD6_&;LhVdDY*=GDORoPcqY2 z04!jc>SILpxjJltdix3mNkGt5?88`AX?UR66(DYUE0J4$kkNe))2P7y5&IhCAy)mVTG-U{tksh)+cLW6Tiur~`5 zEeko-pNXpgG65h900siUAOOe)0CefISE0*Y(pz+Do3uo+4XMR8lvNxK9O%vN_$W!7 z?kzfrU?9AYNDvu;Zhb^N`Rd`T0fK=^eMDCg3_NU8cM)|TQjZ3H>?2yY1-3P%mMwHk z_-A?`uCHj_G=Gg623!C*pZMoUU_@Wh#GKAexVW&FczVxW128JL&y3~MW-QE|vw&PU z{@KjD=pydrPH$fWfI3FycI$D^)ajFJ3*n#?*0lG*=Bab%E=s%~G*x#;<#y{v%nT9R2AMVRd)&8Ve(s!k zb}Pivs4QfKctF|;SChiP#uU-2)edgQqr+~`SM3K=L@P7Kr#vgV65d3R=%dX8s{vpQ zkA1ZXuojf>z;)vE(K^Xpv2e!ZIrC@YG!bCkX9Mnyb3SeA;#{KluAz5J!UhzaGabU@ zF`wo-AeILvr;7M)*yVBa0Q^1xA8spN4tV@-_W@{5wMv&U{Yao7Rm7Vpwq+i`a-Tw5 z?gQupfQdKghl`29ZD-Z^2TgPafK&iTBOV!CuelyuWKY&Wj938R#R;nXb0|PG04%*l zJPzt&m>iOx>>iNBKI0Ea8 z!O;LSXU;V4V}1wodzjxE4S)ge9_CL`{2pUE3taA?6gFmo4J@!TP~jC_&E`A)U)Z` z&x&4WMfb9zd90`zD>~1DkFuf^es09in_17JtfwjK>A`w_iB%mtz;cU7&h&X3G2vGh zoWY6~@$)L4+5k;;vG?6xYG%vWKwsuR%!VFgdLq*|GTmT$JEjjux_SNj^$TOw(7Cyx z84H|Yfj9X%i$@}khja-8|A6HlWd2pmAJ6=knePrRpJM(VcX8Y!S>PHE(SMjRmdnK~ zaGHTOVE)gUKgfI)%r}Tj7q6{HGE@gYXSu`ZU;tp84kj($)4aQm4^RzB+`~gWw+3x@ zfM=L5zC$|se_E#9tGYn|5$%qy)qRBi&I~hcD{h z#(c||uM6`D<{QZEy|~?6&xqDBqHqRu4+FY|0X@Nh&hnh+v!WMR(Q9mIDjRCafO45{ z7V|ln@2s+CdV4cN0yB(dKvNmeBs`G-;LZd9+=-73SI?J5sq*_A+KvZqnGJAu<!iStOwmpp3(UHm#G#w}g zXwE)?Ndv_IaV4;0pcp7F1j?{D9q2ho3=~HLtFd?|a2Sh!2O(L{W)&G z&TIQO43Gdou-;EtZzt9}gXNy(Xl6xwb=W&6q15j5`BVZtIY#Lj!R^0KRPB>hy9s}1 zhF;9@Ju?hv1?#xIEw>-%cFFCz+7W$7-UJOEOz*3X7^6w=z|YyDgS?#u z!)Gf;{nd0;R!mi87cM`WqMny>d9*!%0|4F$j2pixQv zG>l){tM-lkRk@1Gxm-@-awwNxE|a*71@#c&v zMU2NWvL*#V<1FKUoSuC}#k%UiQ-O@3BEfuQlHl&?u@4*Xi0xh8Ok#dhmdD*Yd~fFpR^2lwqQ)c_BshV=p&P zq~@UUIc5%Eim|p4mL=(L(T*%h|Crl%(0$?Yv<}16xXhyEG^l?AduNlpZY<^SeiyHY z`-c+TR72?*WxP2=5keVPKYsofO zAG%#C1*_?%7nISrs`>tsgW(@|92zl@0FReO1Dc(BJG;uUSqgATh8owov@ZGswBY03 zLwO)wo^1&>H(GYBG#fJiqrUewX)KUPm1=0&k8K9n1!!XgpH`V&H&(H#c$HB&X;zC+I?vo##6I*D=nCyk*M}%dIjBIvr{|q zEih3za1GuLOdKU*&2N>1f-l%XEY1X&+W_E|MCHhn($#_-)=@pj@pJNR0O%W1`To0^ z90kZVgLiuE%=V*~&meEA{yd@k4U8OK6D3?-nsLRp3{#NxO959R~4B-8q>ei&n;CSz#Rkcv=CugA>CF+Wv){#2l^IjdPPEn0QV#AoF=tW)CVllm6-KJLm5qi5; zE}QTw8bHrI(=XGi@OejZ`$>NG^Po2ys0_q%JTXPN9dA&o*;?6x%CxFZ01?NZOTEHw zDVa8*SuXFTVJSa!S}oi37igI+Og}tc33gzC=4@ar8`#DM7LbALv|l?Re|Bm-E!#oq z293<7^jBGrsg`-sFEpY64qSHl&dg2A1>hn90XWOIgGZ^yK5rD$|3N(l*wu&pkvEH{ z=4ooz&#fQgBrJ1O*9D0@-QeBMno zG(p3!3>z;gM`Q?!tbE>`YD1>I$K}2;0JlzjB=z6i(`OmT7vwOrQ;Rcc=u^^^d{H?~ zaj7xxPB1A47)u0zb}Dr9UZxdq7()lrkfv?sp`Olj`J)QSyd!wWC(}@u%Z5BfncUMn zmK(=Ybe5+mk@yFtuj@WmEuPM5>q9D+yE&Fv!)$vN zpsL|u@9Z(^Osfi{+$Ca7jo0$~wDAq&)lq7#w`NbeJx0w)3!dTPp#UTIK9!cqo~}C| zBz^fgo}YKJ$GX@}d4eDC;^cS04}2iyc$PALW?%4RXDP@jfqs@k0Qv{(Nu0 zvm@0&AE2e8%QsYvX{@E3LAjjAWm}FpCegE=zLoBi3*}&TQQIacuW^Vv)Vf5z!85cQ z88pEEx)uO5>;H8icbw>D?#%)y0f6hY;);!L)DrjhQd_{dlb(Y{G?hN@ao zWvX2cWN$NH>G2Mu(wF9?GZNrDUnL#U6w0Mo5ws%5r}UyT$uMSf2mVEZhVd^p{1wMQ z4|G)%JA%)!t+xX_1^`>=EGjj+(twp3qejq;-TP3$KVFP&w4yt}p|`^1mewjH*%T-n zFS?3(fi@FFLbs1mwOX0$Reh82|tQYMO6a|!cn%%8<}8?oI?X8(fk3r_W_1HNK=TgEE9 z$2+UCGcUGre7-N>8)89QfDiz9isPjXO3nj6^ZU3>yj^1WW{4k%0&JGM0@aA~1TThh z4b|>Rq`59hmyC01LuLO6uidf3(Y-ZHTflg$yQmA}L%e1zbx(l1XmPI0c)%X7G3ws1 zl@E|JH5)Kn7dn{@kf_o3rRu~jmdADfP zC|e~DjZ4aLq*VpB-z{Rr?SaC(MS@wVLQObHyL)%Km$v`zw*@EQCh`^LG^d~L#za2= z3?HXPdPjG4^LtsffIl%H^NLST23+Xx|8| zo-7jP%p9c_>{=J^oG5a4-hYJSkhJvXs1$)=QkOv;Tei- zS7uD&)pu*dix%@A%9POIYX)2Le8US`Zu(2 z40$^ZgJFcwIa=&po27IX{M(tOUa?;20C3$4Cj801B%6~o zQ5@Ud#);`u;cNg-5r+EW=y(Ig79b@?{&>9QN?@p=1^uhHdo+G##-G9`Wiu5ijV zlb`Xk4vI39__b#a=U#uoZwv4MShxxiP-?z+%|9v{tw~hIpXTEmK z_Zjn@$Eee{KjW&4zRc65`j+u(#>31g8R18)@F!BJOD7NEYUWE~zL%Nr6!TqT!}l^@ zEb~3cd>=92e@$i_&y3N`IExt%GUKPrH<uZ;QPnJ>tEuQ8vQ zz>HrrqhQ8Inei!RY{q;aGT#{*hVK0z#F^`JzT!W+bxGni?io393nnp-yArWX+hWez@eGq zHuE#q{RZnk!aCof+Ymqn2M~g>4CmALS-y{c%6y;kY1}|1q`Xz!ho`yp@a?2SQ-Grl z04DSRIPU-xRx!gXoPpPsuPEx>9pL@F-P7)DjpZAuqxdz~u5^G^F{9OFay^$7oN)hz`CcWu=_`s?7g_i@UBv-oS)dP>dpOnqZx;MJ(E)zqmnq+<4j6ZH z9Pu)b^3Y86(aB2k*5%U4smfvMcuF6G5v~ckoWLQgL5vI2$52XgllQ~h)u()I`BIlS8t1adL;R$#`64b>(3We&6G0@l7swaOveM{CR%|1k zcvO`p+{c8`T(0Lb-B2;$%l!4pFalJPzE*{?a!NcM#i<(!(5Cbk7*KzH$NH9`(!?8h zwLV8aMwcV`HIF+TJK7&0jbp<|zFtgYhQ<7P;yZ4CpA0RO1No)xR0?)V(yIeKbHuQ? z*K+`R6jbzoFbCj{Kx+D9IqIs{N+mtg76*3Zhy>Z6XY>({%C~cQikH+p4tX!oMRQ^L z&paPnDFZPmePbZw@O$rP%SF>dw@O z7hn-j|2V$G+@GYD!6JT_6*)jXFQJ76Cfvi9v<5uCiTpBQ4X5ui2$;{C%A@*6XWC*1 z6L~Mjk@F}?e~>TK*)+N(ay$nt53+Nb!_MhT{ysB==qA8-^o=3FNN!k%pUdLwUZ#J{ z5zikS$eiXt=1cw<;CDLIO427W0G$E!VF0rkz#sC4Ygwcf3l%_nf?R=SjqHGv_%2p zc`Y=fweVQ_S^^R@Bu#~$?&Fboje$JEKwg|m0SrJ(KCuq)>Gu)$>;m=dvGkFwuqi8C z#tNTjg%7a8AnS2+xtsMZV|@o%UkBFrqe(-hr_X1F|73-0SYdz_HQ@4PRv5<$x3I#i z6gLEo1FUZb>)Xoua#`QsS2;fCvWAg#k=r0I3Y%B{p=D4eet? z9hg3b>9;feSpr}Je98b`X8?CHfC2{4ngM*nt2&ASq%eRs4B$aFw3iKSV?!ZK@5%HS zrmsT)xc>4Pz-9&j3}6ETxJYvg@CE}YV}-35z%^Dlo9O{Iw2bNJc=t46`X#nAWj62s zM;O2YZV2PGP{lyV;X_IKY#xbDJQW!{5{ntgC?1Jo26B-Ne!@Ufn0_zQv!?O>-^&Pp zU?A@^kmne{F&>E&25_B6BAx+^WB}b6z|(B#V>a|E18B|kJD7gkG~WLK2JjvOc%A_a zVE{WBfSUn)&Hyw9(2W5!VgPH|&?{`{VFqxO?cB=raFZLBa>KtE!2Jy13LmSh8NfMS z3okH$vuw!C0Loe4B&Kg-LvxvalI?^s-8|2R#&Cn50ZeClHAg*DW~hMAxJRX+R+1wL z8ewBFdWuh(Kv5AG11W{1%e7ptmo%CfdfG_|~g#h?<_0F~-Xa45! z-Q!2TYnGT@tx{G&&N!Xp=Z*Y)oS&EQb2bC%uCk!UyA+T4j0Acv z_HN_nk2%h9@YgASQU^^iUQvpS`6@MJ7V;9X?CfznfW01oXE}09NmB9cn;a1~xBd6aH)y8M*lU!OOG?<~WSo(N!Eqy}9^(o`8nGydG+QMx4oe8)-2 zUjn&H#4vLXO<=K+PZ^_N@fI#uwgh;xd6`y;rQ6RfeUgrGHZYq66e^ScMXBPPxS0!yupLaQ@u3o1lw>uqwe(*B?SnMGG z5Fl@#`T@~r^HeyB&ztuF{-6;5Te7Z4HTEkr7Qe@F!pU zRDHmF_2Wonz;^thB-Zg)R`_h!?RNb6*iQcK4C=t=>+=;fd`^5z>A(_Y@DJ)td<&B4 zhi^#4AHb!&1>k>60l{YkrhaUp5Ti1rmjxCs6RkzZz@}xQmG{)|noAh;zj$&*;}sRJ mqrDFTZZ)~-vgQ&3@PCis3c;`GBS4m3)?DF9hXvrS>i>T|?>Afk diff --git a/docs/public/config/failsafe/parameters.json b/docs/public/config/failsafe/parameters.json index 04d63a7b23..1389314335 100644 --- a/docs/public/config/failsafe/parameters.json +++ b/docs/public/config/failsafe/parameters.json @@ -1 +1 @@ -{"parameters": [{"category": "Standard", "default": 75, "group": "UAVCAN Motor Parameters", "longDesc": "Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness.", "max": 250, "min": 10, "name": "ctl_bw", "shortDesc": "Speed controller bandwidth", "type": "Int32", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "UAVCAN Motor Parameters", "longDesc": "Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction.", "max": 1, "min": 0, "name": "ctl_dir", "shortDesc": "Reverse direction", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "UAVCAN Motor Parameters", "longDesc": "Speed (RPM) controller gain. Determines controller\n aggressiveness; units are amp-seconds per radian. Systems with\n higher rotational inertia (large props) will need gain increased;\n systems with low rotational inertia (small props) may need gain\n decreased. Higher values result in faster response, but may result\n in oscillation and excessive overshoot. Lower values result in a\n slower, smoother response.", "max": 1.0, "min": 0.0, "name": "ctl_gain", "shortDesc": "Speed (RPM) controller gain", "type": "Float", "units": "C/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.5, "group": "UAVCAN Motor Parameters", "longDesc": "Idle speed (e Hz)", "max": 100.0, "min": 0.0, "name": "ctl_hz_idle", "shortDesc": "Idle speed (e Hz)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 25, "group": "UAVCAN Motor Parameters", "longDesc": "Spin-up rate (e Hz/s)", "max": 1000, "min": 5, "name": "ctl_start_rate", "shortDesc": "Spin-up rate (e Hz/s)", "type": "Int32", "units": "1/s^2"}, {"category": "Standard", "default": 0, "group": "UAVCAN Motor Parameters", "longDesc": "Index of this ESC in throttle command messages.", "max": 15, "min": 0, "name": "esc_index", "shortDesc": "Index of this ESC in throttle command messages.", "type": "Int32"}, {"category": "Standard", "default": 20034, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status ID", "max": 1000000, "min": 1, "name": "id_ext_status", "shortDesc": "Extended status ID", "type": "Int32"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status interval (\u00b5s)", "max": 1000000, "min": 0, "name": "int_ext_status", "shortDesc": "Extended status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "ESC status interval (\u00b5s)", "max": 1000000, "name": "int_status", "shortDesc": "ESC status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 3, "default": 12.0, "group": "UAVCAN Motor Parameters", "longDesc": "Motor current limit in amps. This determines the maximum\n current controller setpoint, as well as the maximum allowable\n current setpoint slew rate. This value should generally be set to\n the continuous current rating listed in the motor\u2019s specification\n sheet, or set equal to the motor\u2019s specified continuous power\n divided by the motor voltage limit.", "max": 80.0, "min": 1.0, "name": "mot_i_max", "shortDesc": "Motor current limit in amps", "type": "Float", "units": "A"}, {"category": "Standard", "default": 2300, "group": "UAVCAN Motor Parameters", "longDesc": "Motor Kv in RPM per volt. This can be taken from the motor\u2019s\n specification sheet; accuracy will help control performance but\n some deviation from the specified value is acceptable.", "max": 4000, "min": 0, "name": "mot_kv", "shortDesc": "Motor Kv in RPM per volt", "type": "Int32", "units": "rpm/V"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor inductance in henries. This is measured on start-up.", "name": "mot_ls", "shortDesc": "READ ONLY: Motor inductance in henries.", "type": "Float", "units": "H"}, {"category": "Standard", "default": 14, "group": "UAVCAN Motor Parameters", "longDesc": "Number of motor poles. Used to convert mechanical speeds to\n electrical speeds. This number should be taken from the motor\u2019s\n specification sheet.", "max": 40, "min": 2, "name": "mot_num_poles", "shortDesc": "Number of motor poles.", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor resistance in ohms. This is measured on start-up. When\n tuning a new motor, check that this value is approximately equal\n to the value shown in the motor\u2019s specification sheet.", "name": "mot_rs", "shortDesc": "READ ONLY: Motor resistance in ohms", "type": "Float", "units": "Ohm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "UAVCAN Motor Parameters", "longDesc": "Acceleration limit (V)", "max": 1.0, "min": 0.01, "name": "mot_v_accel", "shortDesc": "Acceleration limit (V)", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 3, "default": 14.8, "group": "UAVCAN Motor Parameters", "longDesc": "Motor voltage limit in volts. The current controller\u2019s\n commanded voltage will never exceed this value. Note that this may\n safely be above the nominal voltage of the motor; to determine the\n actual motor voltage limit, divide the motor\u2019s rated power by the\n motor current limit.", "min": 0.0, "name": "mot_v_max", "shortDesc": "Motor voltage limit in volts", "type": "Float", "units": "V"}, {"category": "Standard", "default": 2, "group": "UAVCAN GNSS", "longDesc": "Dynamic model used in the GNSS positioning engine. 0 \u2013\n Automotive, 1 \u2013 Sea, 2 \u2013 Airborne.\n ", "max": 2, "min": 0, "name": "gnss.dyn_model", "shortDesc": "GNSS dynamic model", "type": "Int32", "values": [{"description": "Automotive", "value": 0}, {"description": "Sea", "value": 1}, {"description": "Airborne", "value": 2}]}, {"category": "Standard", "default": 1, "group": "UAVCAN GNSS", "longDesc": "Broadcast the old (deprecated) GNSS fix message\n uavcan.equipment.gnss.Fix alongside the new alternative\n uavcan.equipment.gnss.Fix2. It is recommended to\n disable this feature to reduce the CAN bus traffic.\n ", "max": 1, "min": 0, "name": "gnss.old_fix_msg", "shortDesc": "Broadcast old GNSS fix message", "type": "Int32", "values": [{"description": "Fix2", "value": 0}, {"description": "Fix and Fix2", "value": 1}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the dimensionality of\n the GNSS solution is less than this value. 3 for the full (3D)\n solution, 2 for planar (2D) solution, 1 for time-only solution,\n 0 disables the feature.\n ", "max": 3, "min": 0, "name": "gnss.warn_dimens", "shortDesc": "device health warning", "type": "Int32", "values": [{"description": "disables the feature", "value": 0}, {"description": "time-only solution", "value": 1}, {"description": "planar (2D) solution", "value": 2}, {"description": "full (3D) solution", "value": 3}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "name": "gnss.warn_sats", "shortDesc": "", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "max": 1000000, "min": 0, "name": "uavcan.pubp-pres", "shortDesc": "", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \". Example \"PX4 \" -> 1347957792 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel. Note: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change. Triggers when the airspeed change within this window is negative while throttle increases and the vehicle pitches down. Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions. Relies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) and measured airspeed. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good. Set to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.55, "group": "Airspeed Validator", "longDesc": "The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.001, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for synthetic airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision. Set to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using an RC AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio", "name": "FW_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "This parameter scales the signal sent to the rate controller during system identification.", "max": 6.0, "min": 0.1, "name": "FW_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio", "name": "MC_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation, which in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low. This has to be lower than the critical threshold. This threshold commonly will trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low. This has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events the specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification. Setting this parameter to 782090 will disable the startup tune, while keeping all others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected checks in the commander, setting it to 0 keeps them enabled (recommended). We are generally recommending to not fly with the USB link connected and production vehicles should set this parameter to zero to prevent users from flying USB powered. However, for R&D purposes it has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_* parameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods: - one arm: request authorization and arm when authorization is received - two step arm: 1st arm command request an authorization and 2nd arm command arm the drone if authorized Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer. Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited. A negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the SD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition. 1: Arming/disarming triggers when holding the momentary button down for COM_RC_ARM_HYST like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Measures taken when a check defined by EKF2_GPS_CHECK is failing.", "name": "COM_ARM_WO_GPS", "shortDesc": "GPS preflight check", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Disabled", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed 1: Allow disarming in multicopter flight in modes where the thrust is directly controlled by thr throttle stick e.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which datalink loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature (see COM_RC_OVERRIDE). Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed).", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below the estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any auto mode other than RTL or Land. Taking over in any manual mode is still possible. Starting from 90% of the maximum flight time, a warning message will be sent every 1 minute with the remaining time until automatic RTL. Set to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss' flag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode.", "name": "COM_POSCTL_NAVL", "shortDesc": "Position mode navigation loss response", "type": "Int32", "values": [{"description": "Altitude mode", "value": 0}, {"description": "Land mode (descend)", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Set to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold. See COM_POS_LOW_EPH to set the failsafe threshold. The failsafe action is only executed if the vehicle is in auto mission or auto loiter mode, otherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold. Local position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT), and a high failsafe threshold (COM_POS_FS_EPH). Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed in which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which RC loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "RC loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Commander", "longDesc": "The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.", "max": 1500, "min": 100, "name": "COM_RC_ARM_HYST", "shortDesc": "RC input arm/disarm command duration", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input.", "max": 4, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "RC control input mode", "type": "Int32", "values": [{"description": "RC Transmitter only", "value": 0}, {"description": "Joystick only", "value": 1}, {"description": "RC and Joystick with fallback", "value": 2}, {"description": "RC or Joystick keep first", "value": 3}, {"description": "Stick input disabled", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost. This must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable RC stick override of auto and/or offboard modes", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold the autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "RC stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed is exceeded before detecting the freefall. This is a safety feature to ensure the drone does not turn on after accidental drop or a rapid movement before the throw. Set to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered. Failsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected. See COM_WIND_MAX to set the failsafe threshold. If enabled, it is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set RC loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}], "category": "Standard", "default": 1023, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 1023, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_A_IGATE", "shortDesc": "Gate size used for innovation consistency checks for range aid fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be played via buzzer or ESCs, if supported. The alarm will sound after a disarm, if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. -", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. It is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady state error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the current body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per second).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing. If set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits.", "max": 15.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in the loiter-down waypoint before the final approach. Otherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway. At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Geometry", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Geometry", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Launch detection", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Launch detection", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 0, "group": "FW Launch detection", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Not compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Launch detection", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "name": "NPFG_EN_MIN_GSP", "shortDesc": "Enable minimum forward ground speed maintaining excess wind handling logic", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW NPFG Control", "increment": 0.5, "longDesc": "The maximum value of the minimum forward ground speed that may be commanded by the track keeping excess wind handling logic. Commanded in full at the normalized track error fraction of the track error boundary and reduced to zero on track.", "max": 10.0, "min": 0.0, "name": "NPFG_GSP_MAX_TK", "shortDesc": "Maximum, minimum forward ground speed for track keeping in excess wind", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination. If false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "name": "NPFG_TRACK_KEEP", "shortDesc": "Enable track keeping excess wind handling logic", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Disabling this parameter further disables all other airspeed incrementation options.", "name": "NPFG_WIND_REG", "shortDesc": "Enable wind excess regulation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Path Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second. Applied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW Path Control", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Path Control", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 65.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Path Control", "increment": 0.5, "max": 30.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve. This value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of 0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX. Set negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX Set to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with the throttle set to FW_THR_MAX and the airspeed set to the trim value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced.", "max": 15.0, "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX.", "max": 5.0, "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers: - Rate controller: output scaling - Attitude controller: coordinated turn controller - Position controller: airspeed setpoint tracking, takeoff logic - VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW TECS", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 60.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 0.4, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Should be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW TECS", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout. If set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW TECS", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW TECS", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints. In manual modes: maximum climb rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW TECS", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle. A negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW TECS", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW TECS", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW TECS", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW TECS", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW TECS", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW TECS", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW TECS", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints. In manual modes: maximum sink rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW TECS", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control applies to speed vs height errors. 0 -> control height only 2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW TECS", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW TECS", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model of the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW TECS", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW TECS", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW TECS", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW TECS", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW TECS", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW TECS", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC to FW_LND_THRTC_SC*FW_T_ALT_TC. -1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW TECS", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW TECS", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Motor failure triggers only below this current value", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Threshold", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Motor failure triggers only above this throttle value.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Throttle Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 100, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Time Threshold", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "RC Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude FLW_TGT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port. In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. Set this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup.", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover (or Unicore primary) antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux) antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. (Note: the Unicore primary antenna is the one connected on the right as seen from the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use. Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. 'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures reported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. motor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and positive thrust of the tail rotor is expected to rotate the vehicle clockwise. Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction which is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag. This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch by aligning the lowest rotor drag with zero compensation. For symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle. For lift profile blades this is typically a command resulting in slightly negative collective blade angle. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy. This requires a symmetric setup where the servo horn is exactly centered with a 0 command. Setting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method. If set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state. Only used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing. Has to be set lower than the expected minimal speed for landing, which is either MPC_LAND_SPEED or MPC_LAND_CRWL. This is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 0, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 1, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 2, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Default to 1, switch to 2 if GCS sends version 2", "value": 0}, {"description": "Always use version 1", "value": 1}, {"description": "Always use version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers before takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive Decrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left and the right stick to the lower right at the same time until the gesture kills the actuators one-way. A negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "max": 3600, "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Mission", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 30.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure: gripper: NAV_CMD_DO_GRIPPER has released before continuing mission. winch: CMD_DO_WINCH has delivered before continuing mission. gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW has reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. Has no effect on mission validity. Set a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing. Then vehicle will loiter in this altitude until further command is received. Only applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to if not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing. Validity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in FW mode (e.g. for Loiter mode).", "max": 1000.0, "min": 25.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, excluding landing commands. Requires a distance sensor to be set up. Note: only prevents the vehicle from descending further, but does not force it to climb. Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this mode without specifying an altitude (e.g. through Loiter switch on RC). Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\"). Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion. Assumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation.", "max": 2, "min": 0, "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_PITCH", "shortDesc": "Offset for pitch channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_ROLL", "shortDesc": "Offset for roll channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_YAW", "shortDesc": "Offset for yaw channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_PITCH", "shortDesc": "Range of pitch channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration. This provides smoother flight but slightly worse tracking in position and auto modes. Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE 1 just deceleration 4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height 0: relative earth frame origin which may drift due to sensors 1: relative to ground (requires distance sensor) which changes with terrain variation. It will revert to relative earth frame if the distance to ground estimate becomes invalid. 2: relative to ground (requires distance sensor) when stationary and relative to earth frame when moving horizontally. The speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Does not apply to manual throttle and direct attitude piloting by stick.", "max": 1.0, "min": 0.0, "name": "MPC_HOLD_DZ", "shortDesc": "Deadzone for sticks in manual piloted modes", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle. A lower value leads to smoother motions but limits agility. Setting this to the maximum value essentially disables the limit. Only used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value between \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\" Value needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to \"MPC_LAND_SPEED\" Value needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available, limit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 1000.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this controls the maximum allowed horizontal displacement from the original landing point.", "min": 0.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed. The descend speed is amended: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode. Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized or Altitude mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode Setting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are: Direct velocity: Sticks directly map to velocity setpoints without smoothing. Also applies to vertical direction and Altitude mode. Useful for velocity control tuning. Acceleration based: Sticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode. Rescale to hover thrust estimate: Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output. No rescale: Directly map the stick 1:1 to the output. Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive. Rescale to hover thrust parameter: Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value. With MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). Used for initialization of the hover thrust estimator (see MPC_USE_HTE). The estimated hover thrust is used as base for zero vertical acceleration in altitude control. The hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority. With airmode enabled this parameters can be set to 0 while still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated. To avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes. Any higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller. This parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX. The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity. A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_XY_MAN_EXPO", "shortDesc": "Manual position control stick exponential curve sensitivity", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral Allows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes. Any higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_YAW_EXPO", "shortDesc": "Manual control stick yaw rotation exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_Z_MAN_EXPO", "shortDesc": "Manual control stick vertical exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.0, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration. 0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display. Resolution is limited by OSD to 15 discrete values. Negative values will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width. This is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "name": "PD_GRIPPER_EN", "rebootRequired": true, "shortDesc": "Enable Gripper actuation in Payload Deliverer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 3.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised. If the gripper has no feedback sensor, it will simply wait for this time before considering gripper actuation successful and publish a 'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC10_DZ", "shortDesc": "RC channel 10 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC11_DZ", "shortDesc": "RC channel 11 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC12_DZ", "shortDesc": "RC channel 12 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC13_DZ", "shortDesc": "RC channel 13 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC14_DZ", "shortDesc": "RC channel 14 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC15_DZ", "shortDesc": "RC channel 15 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC16_DZ", "shortDesc": "RC channel 16 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC17_DZ", "shortDesc": "RC channel 17 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC18_DZ", "shortDesc": "RC channel 18 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC1_DZ", "shortDesc": "RC channel 1 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC2_DZ", "shortDesc": "RC channel 2 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC3_DZ", "shortDesc": "RC channel 3 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC4_DZ", "shortDesc": "RC channel 4 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC5_DZ", "shortDesc": "RC channel 5 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC6_DZ", "shortDesc": "RC channel 6 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC7_DZ", "shortDesc": "RC channel 7 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC8_DZ", "shortDesc": "RC channel 8 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC9_DZ", "shortDesc": "RC channel 9 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. By default this is the throttle channel. Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, but below the minimum PWM value for the channel during normal operation. Note: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost (on receivers that use output a fixed signal value to report lost signal). If set to 0, the channel mapped to throttle is used. Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between the previous, current and next waypoint. Higher value -> smoother trajectory at the cost of how close the rover gets to the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RD_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr WP and curr-next WP interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RD_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the error between the desired and actual yaw. It is also used as the threshold whether the rover should come to a smooth stop at the next waypoint. This slow down effect is active if the angle between the line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the error between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given by the stick inputs. This can be understood as a deadzone for the combined stick inputs for forward/backwards and lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RM_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr waypoint and curr-next waypoint interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RM_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Rover Position Control (Deprecated)", "increment": 0.05, "longDesc": "Damping factor for L1 control.", "max": 0.9, "min": 0.6, "name": "GND_L1_DAMPING", "shortDesc": "L1 damping", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.1, "longDesc": "This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy).", "max": 50.0, "min": 1.0, "name": "GND_L1_DIST", "shortDesc": "L1 distance", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "longDesc": "This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation.", "max": 50.0, "min": 0.5, "name": "GND_L1_PERIOD", "shortDesc": "L1 period", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 150.0, "group": "Rover Position Control (Deprecated)", "max": 400.0, "min": 0.0, "name": "GND_MAN_Y_MAX", "shortDesc": "Max manual yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.7854, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians.", "max": 3.14159, "min": 0.0, "name": "GND_MAX_ANG", "shortDesc": "Maximum turn angle for Ackerman steering", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the derivative gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_D", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the integral gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_I", "shortDesc": "Speed Integral gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the maxim value the integral can reach to prevent wind-up.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_IMAX", "shortDesc": "Speed integral maximum value", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_MAX", "shortDesc": "Maximum ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the proportional gain for the speed closed loop controller", "max": 50.0, "min": 0.005, "name": "GND_SPEED_P", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is a gain to map the speed control output to the throttle linearly.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_THR_SC", "shortDesc": "Speed to throttle scaler", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_TRIM", "shortDesc": "Trim ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Rover Position Control (Deprecated)", "longDesc": "This allows the user to choose between closed loop gps speed or open loop cruise throttle speed", "max": 1, "min": 0, "name": "GND_SP_CTRL_MODE", "shortDesc": "Control mode for speed", "type": "Int32", "values": [{"description": "open loop control", "value": 0}, {"description": "close the loop with gps speed", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode", "max": 1.0, "min": 0.0, "name": "GND_THR_CRUISE", "shortDesc": "Cruise throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough", "max": 1.0, "min": 0.0, "name": "GND_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the minimum throttle % that can be used by the controller. Set to 0 for rover", "max": 1.0, "min": 0.0, "name": "GND_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.31, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "A value of 0.31 is typical for 1/10 RC cars.", "min": 0.0, "name": "GND_WHEEL_BASE", "shortDesc": "Distance from front axle to rear axle", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints in Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. For mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. The minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "longDesc": "0: airframe heading when takeoff is initiated 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF position defined by operator)", "max": 1, "min": 0, "name": "RWTO_HDG", "shortDesc": "Specifies which heading should be held during the runway takeoff ground roll", "type": "Int32", "values": [{"description": "Airframe", "value": 0}, {"description": "Runway", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Max throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Runway Takeoff", "increment": 0.1, "max": 100.0, "min": 1.0, "name": "RWTO_NPFG_PERIOD", "shortDesc": "NPFG period while steering on runway", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up). Must be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD). If set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the algorithm used for logfile encryption", "name": "SDLOG_ALGORITHM", "shortDesc": "Logfile Encryption algorithm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "XChaCha20", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key.", "max": 255, "min": 0, "name": "SDLOG_EXCH_KEY", "shortDesc": "Logfile Encryption key exchange key", "type": "Int32"}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY", "max": 255, "min": 0, "name": "SDLOG_KEY", "shortDesc": "Logfile Encryption key index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "disabled", "value": -1}, {"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 2047, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful when the battery is simulated externally and interfaced with PX4 through MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet. this number defines the (linear) conversion from voltage to Pascal (pa). For the MPXV7002DP this is 1000. NOTE: If the sensor always registers zero, try switching the static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors. This can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on the time derivative of the measured angular velocity, also known as the D-term filter in the rate controller. The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to increase IMU_GYRO_CUTOFF, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro. This only affects the angular velocity sent to the controllers, not the estimators. It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be allowed to publish at. This is the loop rate for the rate controller and outputs. Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities. Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (Roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (Pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (YAW) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance. The GPS selection logic waits until the primary receiver is available to send data to the EKF even if a secondary instance is already available. The secondary instance is then only used if the primary one times out. To have an equal priority of all the instances, set this parameter to -1 and the best receiver will be used. This parameter has no effect if blending is active.", "max": 1, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules. The greater this value, the slower the quad will move. Drag force function of velocity: D=-KDV*V. The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations. The greater this value, the slower the quad will rotate. Aerodynamic moment function of body rate: Ma=-KDW*W_B. This value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. If using FlightGear as a visual animation, this value can be tweaked such that the vehicle lies on the ground at takeoff. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment This value can be measured with a ruler. This corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller when the motor is running at full speed. This value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller when the motor is running at full speed. This value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Quadcopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}, {"description": "Hexacopter", "value": 4}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location Drift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot. WARNING: do not cut the power during an update process, otherwise you will have to recover using some alternative method (e.g. JTAG). Instructions: - Insert an SD card - Enable this parameter - Reboot the board (plug the power or send a reboot command) - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set), the 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses non-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. Note: this is only supported on boards with a separate calibration storage /fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands. WARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus F4 SD variants. If disabled, the preflight checks will not check for the presence of a barometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one. 1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor. If set to 0, the preflight checks will not check for the presence of an airspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Set to 'external HITL', if the system should perform as if it were a real vehicle (the only difference to a real system is then only the parameter value, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup against SYS_PARAM_VER, and if they do not match, parameters are reset and reloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_PITCH", "shortDesc": "Direct pitch input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_ROLL", "shortDesc": "Direct roll input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_THRUST", "shortDesc": "Direct thrust input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_YAW", "shortDesc": "Direct yaw input", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "name": "UUV_INPUT_MODE", "shortDesc": "Select Input Mode", "type": "Int32", "values": [{"description": "use Attitude Setpoints", "value": 0}, {"description": "Direct Feedthrough", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Position Control", "value": 0}, {"description": "Stabilization Mode", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected Agent IP address will be set and used. Decimal dot notation is not supported. IP address must be provided in int32 format. For example, 192.168.1.2 is mapped to -1062731518; 127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero. In a single agent - multi client configuration, each client must have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system. 0: Use the default configuration. 1: Restrict messages to localhost (use in combination with ROS_LOCALHOST_ONLY=1). 2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished. A value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished. A value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to pitch I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode. For standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind. Uses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead. Only active if demanded pitch is below VT_PITCH_MIN. Use VT_FWD_THRUST_SC to tune it. Descend mode is treated as Landing too. Only active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode. Enabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode and the altitude drops below this altitude (relative altitude above local origin), it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above Home if available, otherwise above the local origin) where triggering a quad-chute is possible. At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available. When airspeed is used, transition timeout is declared if airspeed does not reach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if VT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions. Zero will deactivate the slew rate limiting and thus produce an instant throttle rise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight. The check is only active if altitude is controlled and the vehicle is below the current altitude reference. The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current altitude reference. Set to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight in altitude-controlled flight modes. Active until 5s after completing transition to fixed-wing. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Miscellaneous", "name": "UUV_SKIP_CTRL", "shortDesc": "Skip the controller", "type": "Int32", "values": [{"description": "use the module's controller", "value": 0}, {"description": "skip the controller and feedthrough the setpoints", "value": 1}]}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file +{"parameters": [{"category": "Standard", "default": 75, "group": "UAVCAN Motor Parameters", "longDesc": "Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness.", "max": 250, "min": 10, "name": "ctl_bw", "shortDesc": "Speed controller bandwidth", "type": "Int32", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "UAVCAN Motor Parameters", "longDesc": "Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction.", "max": 1, "min": 0, "name": "ctl_dir", "shortDesc": "Reverse direction", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "UAVCAN Motor Parameters", "longDesc": "Speed (RPM) controller gain. Determines controller\n aggressiveness; units are amp-seconds per radian. Systems with\n higher rotational inertia (large props) will need gain increased;\n systems with low rotational inertia (small props) may need gain\n decreased. Higher values result in faster response, but may result\n in oscillation and excessive overshoot. Lower values result in a\n slower, smoother response.", "max": 1.0, "min": 0.0, "name": "ctl_gain", "shortDesc": "Speed (RPM) controller gain", "type": "Float", "units": "C/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.5, "group": "UAVCAN Motor Parameters", "longDesc": "Idle speed (e Hz)", "max": 100.0, "min": 0.0, "name": "ctl_hz_idle", "shortDesc": "Idle speed (e Hz)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 25, "group": "UAVCAN Motor Parameters", "longDesc": "Spin-up rate (e Hz/s)", "max": 1000, "min": 5, "name": "ctl_start_rate", "shortDesc": "Spin-up rate (e Hz/s)", "type": "Int32", "units": "1/s^2"}, {"category": "Standard", "default": 0, "group": "UAVCAN Motor Parameters", "longDesc": "Index of this ESC in throttle command messages.", "max": 15, "min": 0, "name": "esc_index", "shortDesc": "Index of this ESC in throttle command messages.", "type": "Int32"}, {"category": "Standard", "default": 20034, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status ID", "max": 1000000, "min": 1, "name": "id_ext_status", "shortDesc": "Extended status ID", "type": "Int32"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status interval (\u00b5s)", "max": 1000000, "min": 0, "name": "int_ext_status", "shortDesc": "Extended status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "ESC status interval (\u00b5s)", "max": 1000000, "name": "int_status", "shortDesc": "ESC status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 3, "default": 12.0, "group": "UAVCAN Motor Parameters", "longDesc": "Motor current limit in amps. This determines the maximum\n current controller setpoint, as well as the maximum allowable\n current setpoint slew rate. This value should generally be set to\n the continuous current rating listed in the motor\u2019s specification\n sheet, or set equal to the motor\u2019s specified continuous power\n divided by the motor voltage limit.", "max": 80.0, "min": 1.0, "name": "mot_i_max", "shortDesc": "Motor current limit in amps", "type": "Float", "units": "A"}, {"category": "Standard", "default": 2300, "group": "UAVCAN Motor Parameters", "longDesc": "Motor Kv in RPM per volt. This can be taken from the motor\u2019s\n specification sheet; accuracy will help control performance but\n some deviation from the specified value is acceptable.", "max": 4000, "min": 0, "name": "mot_kv", "shortDesc": "Motor Kv in RPM per volt", "type": "Int32", "units": "rpm/V"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor inductance in henries. This is measured on start-up.", "name": "mot_ls", "shortDesc": "READ ONLY: Motor inductance in henries.", "type": "Float", "units": "H"}, {"category": "Standard", "default": 14, "group": "UAVCAN Motor Parameters", "longDesc": "Number of motor poles. Used to convert mechanical speeds to\n electrical speeds. This number should be taken from the motor\u2019s\n specification sheet.", "max": 40, "min": 2, "name": "mot_num_poles", "shortDesc": "Number of motor poles.", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor resistance in ohms. This is measured on start-up. When\n tuning a new motor, check that this value is approximately equal\n to the value shown in the motor\u2019s specification sheet.", "name": "mot_rs", "shortDesc": "READ ONLY: Motor resistance in ohms", "type": "Float", "units": "Ohm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "UAVCAN Motor Parameters", "longDesc": "Acceleration limit (V)", "max": 1.0, "min": 0.01, "name": "mot_v_accel", "shortDesc": "Acceleration limit (V)", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 3, "default": 14.8, "group": "UAVCAN Motor Parameters", "longDesc": "Motor voltage limit in volts. The current controller\u2019s\n commanded voltage will never exceed this value. Note that this may\n safely be above the nominal voltage of the motor; to determine the\n actual motor voltage limit, divide the motor\u2019s rated power by the\n motor current limit.", "min": 0.0, "name": "mot_v_max", "shortDesc": "Motor voltage limit in volts", "type": "Float", "units": "V"}, {"category": "Standard", "default": 2, "group": "UAVCAN GNSS", "longDesc": "Dynamic model used in the GNSS positioning engine. 0 \u2013\n Automotive, 1 \u2013 Sea, 2 \u2013 Airborne.\n ", "max": 2, "min": 0, "name": "gnss.dyn_model", "shortDesc": "GNSS dynamic model", "type": "Int32", "values": [{"description": "Automotive", "value": 0}, {"description": "Sea", "value": 1}, {"description": "Airborne", "value": 2}]}, {"category": "Standard", "default": 1, "group": "UAVCAN GNSS", "longDesc": "Broadcast the old (deprecated) GNSS fix message\n uavcan.equipment.gnss.Fix alongside the new alternative\n uavcan.equipment.gnss.Fix2. It is recommended to\n disable this feature to reduce the CAN bus traffic.\n ", "max": 1, "min": 0, "name": "gnss.old_fix_msg", "shortDesc": "Broadcast old GNSS fix message", "type": "Int32", "values": [{"description": "Fix2", "value": 0}, {"description": "Fix and Fix2", "value": 1}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the dimensionality of\n the GNSS solution is less than this value. 3 for the full (3D)\n solution, 2 for planar (2D) solution, 1 for time-only solution,\n 0 disables the feature.\n ", "max": 3, "min": 0, "name": "gnss.warn_dimens", "shortDesc": "device health warning", "type": "Int32", "values": [{"description": "disables the feature", "value": 0}, {"description": "time-only solution", "value": 1}, {"description": "planar (2D) solution", "value": 2}, {"description": "full (3D) solution", "value": 3}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "name": "gnss.warn_sats", "shortDesc": "", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "max": 1000000, "min": 0, "name": "uavcan.pubp-pres", "shortDesc": "", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \". Example \"PX4 \" -> 1347957792 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460 For CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel. Note: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change. Triggers when the airspeed change within this window is negative while throttle increases and the vehicle pitches down. Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions. Relies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) and measured airspeed. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good. Set to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.55, "group": "Airspeed Validator", "longDesc": "The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.001, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for synthetic airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision. Set to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using an RC AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio", "name": "FW_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "This parameter scales the signal sent to the rate controller during system identification.", "max": 6.0, "min": 0.1, "name": "FW_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio", "name": "MC_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current.", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation, which in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low. This has to be lower than the critical threshold. This threshold commonly will trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low. This has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events the specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification. Setting this parameter to 782090 will disable the startup tune, while keeping all others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected checks in the commander, setting it to 0 keeps them enabled (recommended). We are generally recommending to not fly with the USB link connected and production vehicles should set this parameter to zero to prevent users from flying USB powered. However, for R&D purposes it has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_* parameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods: - one arm: request authorization and arm when authorization is received - two step arm: 1st arm command request an authorization and 2nd arm command arm the drone if authorized Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer. Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited. A negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the SD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition. 1: Arming/disarming triggers when holding the momentary button down for COM_RC_ARM_HYST like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Measures taken when a check defined by EKF2_GPS_CHECK is failing.", "name": "COM_ARM_WO_GPS", "shortDesc": "GPS preflight check", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Disabled", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed 1: Allow disarming in multicopter flight in modes where the thrust is directly controlled by thr throttle stick e.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which datalink loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature (see COM_RC_OVERRIDE). Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed).", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the selected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below the estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any auto mode other than RTL or Land. Taking over in any manual mode is still possible. Starting from 90% of the maximum flight time, a warning message will be sent every 1 minute with the remaining time until automatic RTL. Set to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss' flag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode.", "name": "COM_POSCTL_NAVL", "shortDesc": "Position mode navigation loss response", "type": "Int32", "values": [{"description": "Altitude mode", "value": 0}, {"description": "Land mode (descend)", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Set to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold. See COM_POS_LOW_EPH to set the failsafe threshold. The failsafe action is only executed if the vehicle is in auto mission or auto loiter mode, otherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold. Local position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT), and a high failsafe threshold (COM_POS_FS_EPH). Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed in which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold. A negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which RC loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "RC loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Commander", "longDesc": "The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.", "max": 1500, "min": 100, "name": "COM_RC_ARM_HYST", "shortDesc": "RC input arm/disarm command duration", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input.", "max": 4, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "RC control input mode", "type": "Int32", "values": [{"description": "RC Transmitter only", "value": 0}, {"description": "Joystick only", "value": 1}, {"description": "RC and Joystick with fallback", "value": 2}, {"description": "RC or Joystick keep first", "value": 3}, {"description": "Stick input disabled", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost. This must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable RC stick override of auto and/or offboard modes", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold the autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "RC stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed is exceeded before detecting the freefall. This is a safety feature to ensure the drone does not turn on after accidental drop or a rapid movement before the throw. Set to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered. Failsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected. See COM_WIND_MAX to set the failsafe threshold. If enabled, it is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set RC loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}], "category": "Standard", "default": 1023, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 1023, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_A_IGATE", "shortDesc": "Gate size used for innovation consistency checks for range aid fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be played via buzzer or ESCs, if supported. The alarm will sound after a disarm, if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. -", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. It is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady state error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the current body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per second).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Auto Landing", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing. If set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits.", "max": 15.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in the loiter-down waypoint before the final approach. Otherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway. At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Landing", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Auto Takeoff", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 0, "group": "FW Auto Takeoff", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Not compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout. If set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Auto Takeoff", "increment": 0.5, "max": 30.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30, "group": "FW General", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "max": 3600, "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW General", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 30.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW General", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 60.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 65.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 0.4, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Should be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints. In manual modes: maximum climb rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints. In manual modes: maximum sink rate setpoint.", "max": 15.0, "min": 0.5, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW General", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control applies to speed vs height errors. 0 -> control height only 2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW General", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW General", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Lateral Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second. Applied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle. A negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Longitudinal Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Longitudinal Control", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model of the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW Longitudinal Control", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC to FW_LND_THRTC_SC*FW_T_ALT_TC. -1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination. If false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Factor applied to the minimum and stall airspeed when flaps are fully deployed.", "max": 1.0, "min": 0.5, "name": "FW_AIRSPD_FLP_SC", "shortDesc": "Airspeed scale with full flaps", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve. This value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of 0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX. Set negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX Set to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with the throttle set to FW_THR_MAX and the airspeed set to the trim value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced.", "max": 15.0, "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX.", "max": 5.0, "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers: - Rate controller: output scaling - Attitude controller: coordinated turn controller - Position controller: airspeed setpoint tracking, takeoff logic - VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Motor failure triggers only below this current value", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Threshold", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Motor failure triggers only above this throttle value.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Throttle Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 100, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Time Threshold", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "RC Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude FLW_TGT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port. In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. Set this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup.", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover (or Unicore primary) antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux) antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. (Note: the Unicore primary antenna is the one connected on the right as seen from the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use. Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. 'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures reported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. motor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and positive thrust of the tail rotor is expected to rotate the vehicle clockwise. Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction which is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag. This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch by aligning the lowest rotor drag with zero compensation. For symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle. For lift profile blades this is typically a command resulting in slightly negative collective blade angle. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy. This requires a symmetric setup where the servo horn is exactly centered with a 0 command. Setting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method. If set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state. Only used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing. Has to be set lower than the expected minimal speed for landing, which is either MPC_LAND_SPEED or MPC_LAND_CRWL. This is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more. Decrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 0, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0, selected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 1, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1, selected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone on the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 2, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2, selected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Default to 1, switch to 2 if GCS sends version 2", "value": 0}, {"description": "Always use version 1", "value": 1}, {"description": "Always use version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers before takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive Decrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left and the right stick to the lower right at the same time until the gesture kills the actuators one-way. A negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure: gripper: NAV_CMD_DO_GRIPPER has released before continuing mission. winch: CMD_DO_WINCH has delivered before continuing mission. gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW has reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. Has no effect on mission validity. Set a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing. Then vehicle will loiter in this altitude until further command is received. Only applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to if not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing. Validity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in FW mode (e.g. for Loiter mode).", "max": 1000.0, "min": 25.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, excluding landing commands. Requires a distance sensor to be set up. Note: only prevents the vehicle from descending further, but does not force it to climb. Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this mode without specifying an altitude (e.g. through Loiter switch on RC). Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\"). Set to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion. Assumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation.", "max": 2, "min": 0, "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_PITCH", "shortDesc": "Offset for pitch channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_ROLL", "shortDesc": "Offset for roll channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_YAW", "shortDesc": "Offset for yaw channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_PITCH", "shortDesc": "Range of pitch channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 6.5, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 20.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large control output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration. This provides smoother flight but slightly worse tracking in position and auto modes. Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE 1 just deceleration 4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height 0: relative earth frame origin which may drift due to sensors 1: relative to ground (requires distance sensor) which changes with terrain variation. It will revert to relative earth frame if the distance to ground estimate becomes invalid. 2: relative to ground (requires distance sensor) when stationary and relative to earth frame when moving horizontally. The speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Does not apply to manual throttle and direct attitude piloting by stick.", "max": 1.0, "min": 0.0, "name": "MPC_HOLD_DZ", "shortDesc": "Deadzone for sticks in manual piloted modes", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle. A lower value leads to smoother motions but limits agility. Setting this to the maximum value essentially disables the limit. Only used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value between \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\" Value needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to \"MPC_LAND_SPEED\" Value needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available, limit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 1000.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this controls the maximum allowed horizontal displacement from the original landing point.", "min": 0.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed. The descend speed is amended: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode. Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized or Altitude mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode Setting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are: Direct velocity: Sticks directly map to velocity setpoints without smoothing. Also applies to vertical direction and Altitude mode. Useful for velocity control tuning. Acceleration based: Sticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode. Rescale to hover thrust estimate: Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output. No rescale: Directly map the stick 1:1 to the output. Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive. Rescale to hover thrust parameter: Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value. With MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). Used for initialization of the hover thrust estimator (see MPC_USE_HTE). The estimated hover thrust is used as base for zero vertical acceleration in altitude control. The hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority. With airmode enabled this parameters can be set to 0 while still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated. To avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes. Any higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller. This parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX. The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity. A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_XY_MAN_EXPO", "shortDesc": "Manual position control stick exponential curve sensitivity", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral Allows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes. Any higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_YAW_EXPO", "shortDesc": "Manual control stick yaw rotation exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_Z_MAN_EXPO", "shortDesc": "Manual control stick vertical exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.0, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration. 0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display. Resolution is limited by OSD to 15 discrete values. Negative values will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width. This is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "name": "PD_GRIPPER_EN", "rebootRequired": true, "shortDesc": "Enable Gripper actuation in Payload Deliverer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 3.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised. If the gripper has no feedback sensor, it will simply wait for this time before considering gripper actuation successful and publish a 'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC10_DZ", "shortDesc": "RC channel 10 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC11_DZ", "shortDesc": "RC channel 11 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC12_DZ", "shortDesc": "RC channel 12 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC13_DZ", "shortDesc": "RC channel 13 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC14_DZ", "shortDesc": "RC channel 14 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC15_DZ", "shortDesc": "RC channel 15 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC16_DZ", "shortDesc": "RC channel 16 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC17_DZ", "shortDesc": "RC channel 17 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC18_DZ", "shortDesc": "RC channel 18 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC1_DZ", "shortDesc": "RC channel 1 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC2_DZ", "shortDesc": "RC channel 2 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC3_DZ", "shortDesc": "RC channel 3 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC4_DZ", "shortDesc": "RC channel 4 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC5_DZ", "shortDesc": "RC channel 5 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC6_DZ", "shortDesc": "RC channel 6 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC7_DZ", "shortDesc": "RC channel 7 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC8_DZ", "shortDesc": "RC channel 8 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC9_DZ", "shortDesc": "RC channel 9 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. By default this is the throttle channel. Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, but below the minimum PWM value for the channel during normal operation. Note: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost (on receivers that use output a fixed signal value to report lost signal). If set to 0, the channel mapped to throttle is used. Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs for straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between the previous, current and next waypoint. Higher value -> smoother trajectory at the cost of how close the rover gets to the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RD_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr WP and curr-next WP interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RD_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the error between the desired and actual yaw. It is also used as the threshold whether the rover should come to a smooth stop at the next waypoint. This slow down effect is active if the angle between the line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the error between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given by the stick inputs. This can be understood as a deadzone for the combined stick inputs for forward/backwards and lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower.", "max": 100.0, "min": 0.0, "name": "RM_MAX_THR_YAW_R", "shortDesc": "Yaw rate turning left/right wheels at max speed in opposite directions", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "The waypoint transition speed is calculated as: Transition_speed = Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr waypoint and curr-next waypoint interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition.", "max": 100.0, "min": -1.0, "name": "RM_MISS_SPD_GAIN", "shortDesc": "Tuning parameter for the speed reduction during waypoint transition", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Rover Position Control (Deprecated)", "increment": 0.05, "longDesc": "Damping factor for L1 control.", "max": 0.9, "min": 0.6, "name": "GND_L1_DAMPING", "shortDesc": "L1 damping", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.1, "longDesc": "This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy).", "max": 50.0, "min": 1.0, "name": "GND_L1_DIST", "shortDesc": "L1 distance", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "longDesc": "This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation.", "max": 50.0, "min": 0.5, "name": "GND_L1_PERIOD", "shortDesc": "L1 period", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 150.0, "group": "Rover Position Control (Deprecated)", "max": 400.0, "min": 0.0, "name": "GND_MAN_Y_MAX", "shortDesc": "Max manual yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.7854, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians.", "max": 3.14159, "min": 0.0, "name": "GND_MAX_ANG", "shortDesc": "Maximum turn angle for Ackerman steering", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the derivative gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_D", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the integral gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_I", "shortDesc": "Speed Integral gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the maxim value the integral can reach to prevent wind-up.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_IMAX", "shortDesc": "Speed integral maximum value", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_MAX", "shortDesc": "Maximum ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the proportional gain for the speed closed loop controller", "max": 50.0, "min": 0.005, "name": "GND_SPEED_P", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is a gain to map the speed control output to the throttle linearly.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_THR_SC", "shortDesc": "Speed to throttle scaler", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_TRIM", "shortDesc": "Trim ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Rover Position Control (Deprecated)", "longDesc": "This allows the user to choose between closed loop gps speed or open loop cruise throttle speed", "max": 1, "min": 0, "name": "GND_SP_CTRL_MODE", "shortDesc": "Control mode for speed", "type": "Int32", "values": [{"description": "open loop control", "value": 0}, {"description": "close the loop with gps speed", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode", "max": 1.0, "min": 0.0, "name": "GND_THR_CRUISE", "shortDesc": "Cruise throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough", "max": 1.0, "min": 0.0, "name": "GND_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the minimum throttle % that can be used by the controller. Set to 0 for rover", "max": 1.0, "min": 0.0, "name": "GND_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.31, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "A value of 0.31 is typical for 1/10 RC cars.", "min": 0.0, "name": "GND_WHEEL_BASE", "shortDesc": "Distance from front axle to rear axle", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease. Set to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints in Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. For mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable. The minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up). Must be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD). If set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the algorithm used for logfile encryption", "name": "SDLOG_ALGORITHM", "shortDesc": "Logfile Encryption algorithm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "XChaCha20", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key.", "max": 255, "min": 0, "name": "SDLOG_EXCH_KEY", "shortDesc": "Logfile Encryption key exchange key", "type": "Int32"}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY", "max": 255, "min": 0, "name": "SDLOG_KEY", "shortDesc": "Logfile Encryption key index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "disabled", "value": -1}, {"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}, {"description": "High rate sensors", "index": 11}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 4095, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful when the battery is simulated externally and interfaced with PX4 through MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet. this number defines the (linear) conversion from voltage to Pascal (pa). For the MPXV7002DP this is 1000. NOTE: If the sensor always registers zero, try switching the static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors. This can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on the time derivative of the measured angular velocity, also known as the D-term filter in the rate controller. The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to increase IMU_GYRO_CUTOFF, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro. This only affects the angular velocity sent to the controllers, not the estimators. It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter. A value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be allowed to publish at. This is the loop rate for the rate controller and outputs. Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities. Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (Roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (Pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0.0, "group": "Sensors", "longDesc": "This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment.", "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (YAW) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance. The GPS selection logic waits until the primary receiver is available to send data to the EKF even if a secondary instance is already available. The secondary instance is then only used if the primary one times out. To have an equal priority of all the instances, set this parameter to -1 and the best receiver will be used. This parameter has no effect if blending is active.", "max": 1, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules. The greater this value, the slower the quad will move. Drag force function of velocity: D=-KDV*V. The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations. The greater this value, the slower the quad will rotate. Aerodynamic moment function of body rate: Ma=-KDW*W_B. This value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. If using FlightGear as a visual animation, this value can be tweaked such that the vehicle lies on the ground at takeoff. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment This value can be measured with a ruler. This corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller when the motor is running at full speed. This value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller when the motor is running at full speed. This value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Quadcopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}, {"description": "Hexacopter", "value": 4}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location Drift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot. WARNING: do not cut the power during an update process, otherwise you will have to recover using some alternative method (e.g. JTAG). Instructions: - Insert an SD card - Enable this parameter - Reboot the board (plug the power or send a reboot command) - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set), the 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses non-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. Note: this is only supported on boards with a separate calibration storage /fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands. WARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus F4 SD variants. If disabled, the preflight checks will not check for the presence of a barometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one. 1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor. If set to 0, the preflight checks will not check for the presence of an airspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Set to 'external HITL', if the system should perform as if it were a real vehicle (the only difference to a real system is then only the parameter value, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup against SYS_PARAM_VER, and if they do not match, parameters are reset and reloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_PITCH", "shortDesc": "Direct pitch input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_ROLL", "shortDesc": "Direct roll input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_THRUST", "shortDesc": "Direct thrust input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_YAW", "shortDesc": "Direct yaw input", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "name": "UUV_INPUT_MODE", "shortDesc": "Select Input Mode", "type": "Int32", "values": [{"description": "use Attitude Setpoints", "value": 0}, {"description": "Direct Feedthrough", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Position Control", "value": 0}, {"description": "Stabilization Mode", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected Agent IP address will be set and used. Decimal dot notation is not supported. IP address must be provided in int32 format. For example, 192.168.1.2 is mapped to -1062731518; 127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero. In a single agent - multi client configuration, each client must have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system. 0: Use the default configuration. 1: Restrict messages to localhost (use in combination with ROS_LOCALHOST_ONLY=1). 2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished. A value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished. A value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to pitch I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode. For standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind. Uses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead. Only active if demanded pitch is below VT_PITCH_MIN. Use VT_FWD_THRUST_SC to tune it. Descend mode is treated as Landing too. Only active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode. Enabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode and the altitude drops below this altitude (relative altitude above local origin), it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above Home if available, otherwise above the local origin) where triggering a quad-chute is possible. At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available. When airspeed is used, transition timeout is declared if airspeed does not reach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if VT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions. Zero will deactivate the slew rate limiting and thus produce an instant throttle rise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight. The check is only active if altitude is controlled and the vehicle is below the current altitude reference. The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current altitude reference. Set to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight in altitude-controlled flight modes. Active until 5s after completing transition to fixed-wing. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Miscellaneous", "name": "UUV_SKIP_CTRL", "shortDesc": "Skip the controller", "type": "Int32", "values": [{"description": "use the module's controller", "value": 0}, {"description": "skip the controller and feedthrough the setpoints", "value": 1}]}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file diff --git a/docs/public/middleware/graph_full.json b/docs/public/middleware/graph_full.json index a609e0877f..01bb52fd5b 100644 --- a/docs/public/middleware/graph_full.json +++ b/docs/public/middleware/graph_full.json @@ -1 +1 @@ -{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#7341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#41d842", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8419e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_status", "name": "internal_combustion_engine_status", "type": "topic", "color": "#d84164", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84146", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d85841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d85e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d8a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d88d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d841aa", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d84152", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#62d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#41d848", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d877", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#41a0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance_fused", "name": "obstacle_distance_fused", "type": "topic", "color": "#5c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#7941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#ba41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41a6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#a841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41d8ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8aa41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#73d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d8b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_serial_passthru", "name": "esc_serial_passthru", "type": "topic", "color": "#4148d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#d841cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d89e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#79d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#5cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d87d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d88741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#d8cd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#6241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d84c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d841bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8414c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#44d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d889", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d8a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41cfd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41b2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#4189d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#d8415e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#417dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#4177d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d8418d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d85241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#a8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#4142d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#4441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#bad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41acd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4195d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d84187", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d8cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d84193", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d86441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d84158", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41b8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d8b8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d89341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d895", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d8bc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#44d841", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d84141", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#41d883", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#414ed8", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#d8cd41", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#97d841", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#d89e41", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d84187", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d8d341", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#414ed8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d8d341", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#41d85a", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#4142d8", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#41cad8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d89941", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d89941", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41acd8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d8a441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#a841d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d8d341", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#41d85a", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance_fused", "color": "#5c41d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#6241d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#d841c8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#d84c41", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#d84141", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#62d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#41a0d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#41d8be", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#d841cd", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#41d848", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#d841b6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d84c41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841c8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d841bc", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d88d41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d895", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#a241d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#85d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#7fd841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d8d5", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#73d841", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4154d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d88f", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4154d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d87d", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#62d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#41a0d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#41d8be", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#d841cd", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#41d848", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#d841b6", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#b441d8", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#41acd8", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d84199", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#c6d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8419e", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41d5d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#41d842", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7341d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d7d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d85841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#41d842", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d8419e", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d841a4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#6241d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#c6d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7341d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#d84152", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#56d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#41d842", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d8419e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d8bc41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#4142d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#c6d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7341d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#6ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#50d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#418fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d87541", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#44d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d841c2", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#4177d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d89e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d84175", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#6e41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d88f", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#9dd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#9141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d84158", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#91d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#6ed841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d85e41", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d85241", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d741d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d8418d", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d8c841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d87b41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#4177d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#a8d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#417dd8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d89341", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#41d86c", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d8b2", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#bad841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#5641d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#bad841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d877", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#4177d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d84e", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#b4d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#41c4d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#a2d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84641", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d8ca", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4ad841", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41d5d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841c8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#79d841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#ccd841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#415ad8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#41d860", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#41d871", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#ba41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#7941d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#bad841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84146", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_status", "color": "#d84164", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#41d89b", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d8b8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d84c41", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#7fd841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#d841bc", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41b2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41a6d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d85841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#56d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4195d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d86a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d87041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#44d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d86441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#4183d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d88141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d841b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#4160d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d89e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d89341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d841aa", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d866", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d8b641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#4142d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_esc_serial_passthru", "color": "#4148d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d84193", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d84170", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_obstacle_distance", "color": "#6241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d889", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#6841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d8a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d8a0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41d8ac", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#41d8b2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#8bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d84152", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41d5d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41cfd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#c041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8414c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41b8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#73d841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#416cd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d1d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d85841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#ae41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#d8415e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#8b41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d88741", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#9741d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#4441d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41d854", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d8b041", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8aa41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84181", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#5cd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#4189d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#68d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d8417b", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d8b2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#41d86c", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84146", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#5641d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#62d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#41a0d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#41d8be", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#d841cd", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#41d848", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#41bed8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#d841b6", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#8541d8", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#7fd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#d8418d", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#4183d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#68d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#ccd841", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#41b8d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d841a4", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#416cd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d87d", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#41d883", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#4166d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#41d8d5", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#41d87d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41b2d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#8541d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#416cd8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#6ed841", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#41d5d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#d8c241", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#416cd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#d89e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#d88141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#d8415e", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d84187", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#41d89b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41bed8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#bad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#4177d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d87d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41b2d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#a8d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#d88141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#417dd8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d86a41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#4189d8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#41cad8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#d88141", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#9d41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#6ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#4177d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41b8d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#416cd8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d89941", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41b2d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#6ed841", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#419bd8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#4189d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#4177d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#4166d8", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d841aa", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d877", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#41d88f", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#a2d841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41d8ac", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#8bd841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#7fd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#41bed8", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#4166d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#41bed8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#4189d8", "style": "normal"}, {"source": "t_esc_serial_passthru", "target": "m_voxl_esc", "color": "#4148d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#41d89b", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#7941d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#bad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#4177d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#41d87d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#7fd841", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#4177d8", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d87541", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#8541d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#41cfd8", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#6241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4195d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#416cd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#4177d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#4166d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#4166d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#4ad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#41bed8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#41d8b2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#62d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#41a0d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#41d8be", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#d141d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#d841cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#7fd841", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#41c4d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#41d848", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d87b41", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84641", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d88f", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4ad841", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d84199", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#4189d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41cfd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841c8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#ba41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#4177d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#79d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#73d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#68d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#7fd841", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#4142d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#9d41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d8b2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d8ca", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#7fd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841c8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#ba41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d87b41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#4177d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d84193", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4195d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84181", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#b4d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#5cd841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41a6d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#4177d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#4171d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#416cd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#41bed8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#41d8b2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#62d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#41a0d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#d141d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#d841cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#7fd841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#41d848", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d87b41", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#9d41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d85841", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#41d85a", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#41d842", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#41d842", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#7941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#4189d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#d8415e", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#41bed8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8419e", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#41d842", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41d877", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#4189d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#d8415e", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#bad841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#41bed8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#8b41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#a8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#a2d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8419e", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#41d842", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d842", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#9d41d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d89e41", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#6ed841", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d84158", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#ccd841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#4189d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#7fd841", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d841c2", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d871", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#4177d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#73d841", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d8b8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#4189d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d8418d", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#416cd8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#68d841", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#6ed841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d84c41", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d141d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4195d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#5cd841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d86441", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#50d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#4189d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d88141", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d841b0", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d84e", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#416cd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41bed8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d88d41", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d89341", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8aa41", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d84193", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#4441d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d8417b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d877", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d8c841", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d8d341", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d88f", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#6e41d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#8541d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#9dd841", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#a241d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d8b8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d8ca", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#85d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d8cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#7fd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41cfd8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8414c", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#79d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#7941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d8ca", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d841c8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#4183d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#4177d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#5041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d877", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#4177d8", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d84e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#9d41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41a6d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#4177d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#4171d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#416cd8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#5641d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#cc41d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d8b041", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d741d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d841d3", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d8bc41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84181", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#4177d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84641", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4195d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d8ca", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#85d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d86441", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d84193", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841c8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d87b41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d841b0", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41a6d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#44d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#9d41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#5cd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#4189d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#4177d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#9141d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#4177d8", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#d8bc41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#56d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#41d88f", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4ad841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#7fd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41cfd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#8541d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#73d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84641", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d84c41", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d85e41", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d85241", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d85841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d86441", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d88141", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d88741", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d88d41", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d89341", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d89e41", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d8a441", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#d8bc41", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#d8cd41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d7d841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#aed841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#85d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#7fd841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#73d841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#68d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#5cd841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#50d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#41d842", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41d854", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#41d85a", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41d860", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d877", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d889", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d88f", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d895", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d8b8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d8ca", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d8cf", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41cfd8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41b8d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41b2d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41a6d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#4189d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#415ad8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#4154d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#414ed8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#4a41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#5641d8", "style": "normal"}, {"source": "t_obstacle_distance_fused", "target": "m_mavlink", "color": "#5c41d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#7341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#8541d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#8b41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#9141d8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#9741d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#a841d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#ae41d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#c041d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d841bc", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d8419e", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d841a4", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d8418d", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d84170", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_internal_combustion_engine_status", "target": "m_mavlink", "color": "#d84164", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84146", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#4177d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#7941d8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#9d41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d85841", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#91d841", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d866", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#4189d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#4189d8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d8a0", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#4177d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#416cd8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#5cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#4177d8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d84e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8a6", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84146", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#415ad8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d84c41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41d88f", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#7fd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#ba41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#7941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#4177d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d88d41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4195d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#41d8cf", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d86441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#4189d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d84193", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d8b2", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#5641d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#6841d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41b8d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#41bed8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#41d8b2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#62d841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#41a0d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#d141d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#d841cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41d877", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#7fd841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#41d848", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d87b41", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#56d841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4ad841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#4177d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d86441", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_status", "name": "internal_combustion_engine_status", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#6541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#87d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#d8415d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41a5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#41cdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#4ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#cbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#ba41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#d85241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#5f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#8741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#c5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#d86341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance_fused", "name": "obstacle_distance_fused", "type": "topic", "color": "#d89041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#d8a741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#afd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#5fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#41d861", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41abd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#8141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#c541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d844", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#4144d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d841a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84146", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d8d441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#4841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#4e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#81d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#65d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41b0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_serial_passthru", "name": "esc_serial_passthru", "type": "topic", "color": "#7041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#d87941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d878", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#41d8c7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d84c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#92d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#42d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#41d87d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41c7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#4189d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#415bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#9241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#bad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d8cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d84163", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#d84152", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d85d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#41d889", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41d8ab", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#4178d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#a341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d841d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d84641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41d85b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#41bcd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#417dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#4161d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#af41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#cb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d84190", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d8b841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#76d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#41d8bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#7641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d841b8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#a3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#70d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#d141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d84179", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d8414c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#48d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41d8b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d8a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#41d8d3", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#7b41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#d141d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d86c", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d84179", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#41d8ab", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#41d8c7", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#414ad8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#5941d8", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#41bcd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#419fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41d8ab", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d84179", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d86c", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#4183d8", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#4183d8", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#41bcd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d84141", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#d84641", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#41d8bc", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#70d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d841b2", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#70d841", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#4144d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#41bcd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#419ad8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d84141", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#d87941", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance_fused", "color": "#d89041", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#415bd8", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#4189d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#41c7d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#d84179", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#4183d8", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#7b41d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41d86c", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#d841a1", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#d86341", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#41d8c1", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#a9d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#d8a741", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#7641d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#afd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#4189d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d88541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d89641", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#41d87d", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#415bd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d841a7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#4841d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d8a5", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41c7d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84146", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d850", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#4166d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#87d841", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#c041d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#87d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d844", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d84168", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d844", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d878", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d844", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#53d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#d841a1", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#d86341", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#a9d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#d8a741", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d841be", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#d841b2", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#41d872", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#418ed8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#6ad841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41d8d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#4ed841", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d8417f", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#9241d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7bd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#6ad841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#4ed841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#418ed8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#d87941", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#d84179", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#5f41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#8141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#d84641", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#6ad841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#4ed841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#418ed8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#4183d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#d88a41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d89c41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#8141d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#d84179", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#8741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#8c41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#4194d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#48d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#c041d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#42d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#417dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#416cd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#4178d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d89641", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d84174", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#5941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#bad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#d84152", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8d3", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d8414c", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#41d889", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41d8b0", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41d894", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#417dd8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#6a41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#4178d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#4161d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41d85b", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#a341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d1d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d8b241", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#65d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d84190", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d84157", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d84190", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d841d4", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#4178d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#5341d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41abd8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#5fd841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#41d861", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41d8c1", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#ba41d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d844", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#c5d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d841cf", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#98d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#4189d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d87f41", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#9841d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d866", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d8416e", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41d8d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#8cd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#d8415d", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#d84190", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#81d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#41d84a", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#41a5d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#d841c3", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d8a141", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#d8ad41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#9dd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#41d878", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#d85241", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#53d841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#5fd841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d861", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#5fd841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d861", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#92d841", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_status", "color": "#41d89a", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#d84196", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#4150d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d89641", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#41c7d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#41d87d", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d84146", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d84641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#76d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#af41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#65d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#b441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d84c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d85741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#48d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41d844", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#cb41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d86841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d86e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d87441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_obstacle_distance", "color": "#d87941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d841c9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d855", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d89641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d89c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#4166d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#415bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#4155d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d86c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#d8419c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8c341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#4e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d8c941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d8cf41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d8d441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d84179", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#5941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#cbd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#5f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d84163", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#6541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41d8b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#b4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_esc_serial_passthru", "color": "#7041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#a3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41c1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#8141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84146", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d84185", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d8418a", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d8be41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41b6d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d8cd", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#a941d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#59d841", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d841b8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8b6", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#c0d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#5fd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41b0d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d861", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d878", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#53d841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#4172d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d6d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d3d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d8b841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d85d41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d84157", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41a5d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#65d841", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#5341d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#d841a1", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#d86341", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#4241d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#a9d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#d8a741", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#415bd8", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#4178d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#41d889", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#d841c9", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#d84146", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#41d3d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#b4d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#9241d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#70d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#415bd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#d141d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#d84190", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#d8b841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#d84168", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d86c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#a341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#415bd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d84185", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84146", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#417dd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d84185", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#d88a41", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#c041d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#5941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#d84179", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#4178d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#4178d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41d89f", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#419fd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#d84168", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d86c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#a341d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#41d85b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#a341d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#d84179", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#a341d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#a341d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#4178d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#4178d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#4178d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#4178d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41d89f", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#41d8bc", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#d84179", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#b4d841", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#417dd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d84185", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d84146", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#4178d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d84146", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#70d841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#9d41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#a341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41abd8", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d85741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#c041d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d641d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#417dd8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#4178d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#41d85b", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d86c", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#d8419c", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#d84196", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d8b841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#d84190", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d8d441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d84168", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d8cd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84146", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#d84196", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#d8b841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#41d850", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#4178d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#41d85b", "style": "normal"}, {"source": "t_esc_serial_passthru", "target": "m_voxl_esc", "color": "#7041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#41d8cd", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d1d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#41d85b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d89f", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#41d8bc", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84146", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d84174", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#4178d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#7b41d8", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#d87941", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#415bd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#cb41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#415bd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#4178d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#4178d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d8b841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d8b841", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#d8b841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d8b841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#d8b841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d8b841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#d87f41", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#d841a1", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#c541d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#4241d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#d86341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#8741d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#98d841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#41d8c1", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#d8c941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41abd8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#a9d841", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d1d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#415bd8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d84146", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#c041d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#d8415d", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#4178d8", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d8a141", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d841c3", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#415bd8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d84146", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#c041d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d84163", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#9dd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#4189d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#9841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#4178d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d89f", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d8416e", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#4166d8", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#415bd8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d84641", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84146", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#4178d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d85d41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#8741d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d1d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#4178d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#4172d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#a341d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d866", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#9dd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#5fd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84146", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d6d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#cb41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#4178d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#ba41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#4178d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#87d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#4178d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#4172d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#415bd8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#d85241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84146", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#87d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#4178d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84146", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#c5d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d844", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#4178d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#4172d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d1d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#d841a1", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#c541d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#d86341", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#4241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#8741d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#d8c941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41abd8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#a9d841", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d1d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#415bd8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d84146", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#415bd8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#418ed8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#9241d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d8417f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#41d89f", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#4178d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#418ed8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#4241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#d84196", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#d84190", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#d8be41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d841cf", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41abd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#9241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#d84185", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#4ed841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#48d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#c041d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d8a5", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#bad841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#92d841", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d8414c", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#417dd8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d84a", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#4166d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84146", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#4150d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#41d889", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d89f", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#41bcd8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#8c41d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41b0d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#a341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41abd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#b441d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d84c41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#c041d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#42d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#cb41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d86841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d87441", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d841d4", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#4189d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#417dd8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#4178d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#416cd8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d88a41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#415bd8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d841a7", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#4150d8", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#414ad8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4241d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#4841d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#4e41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d84185", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d8c941", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#5341d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d84179", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d6d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d8416e", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d8a5", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d84163", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41d8b0", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#d84152", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8b6", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41c7d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d3d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84146", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d88a41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#4178d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#4189d8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#d841c9", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d866", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d85d41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84146", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d841d4", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#5341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d1d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84146", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#8741d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d89641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d1d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84146", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#c5d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d844", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#4178d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d1d841", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#c0d841", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#4183d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#4178d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#5341d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d878", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d1d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#5fd841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d8b241", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#cb41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d86841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d86e41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d87441", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#4189d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#4841d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#9841d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#4e41d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d866", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d6d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#c041d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#41d8a5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#8741d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d89641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d1d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d84146", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d844", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#415bd8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8d3", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#4183d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#4241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#c041d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#d84163", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#a341d8", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#41d89f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d84146", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d87441", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d88541", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_obstacle_distance_fused", "target": "m_mavlink", "color": "#d89041", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d8be41", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8c341", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d6d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d1d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#b4d841", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#a3d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#92d841", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#8cd841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#87d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#81d841", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#7bd841", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#5fd841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#4ed841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#48d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41d844", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d88e", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#41d889", "style": "normal"}, {"source": "t_internal_combustion_engine_status", "target": "m_mavlink", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d89f", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d8a5", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41d8ab", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41d8b0", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41d8c1", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#41d8c7", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#41cdd8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41c7d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d3d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41a5d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#418ed8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#4189d8", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#4183d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#417dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#4178d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#4172d8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#4161d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#415bd8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#4150d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#4144d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#4841d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#4e41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#5341d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#5941d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#5f41d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#7641d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#8741d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#8c41d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#9841d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#af41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#c041d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d841be", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d841b8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d84185", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d84179", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d84163", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84146", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#afd841", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#4178d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#5f41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#c041d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#8741d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#6541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d89641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41abd8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#41cdd8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#cbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#4194d8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d855", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#4178d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41abd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d89f", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#8741d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41a5d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d841d4", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#417dd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#415bd8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d883", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d1d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#7641d8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41c1d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84146", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#5fd841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d88541", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#4178d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#7641d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41c7d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84146", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#cb41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d86841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#b441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d84157", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d1d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84146", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#b4d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#5341d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d8cf41", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#d841a1", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#c541d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#d86341", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#4241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#8741d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#d8c941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41abd8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#a9d841", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d1d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#415bd8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d84146", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84146", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#4178d8", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_full_no_mavlink.json b/docs/public/middleware/graph_full_no_mavlink.json index 2164f67cc1..6f6ffe10df 100644 --- a/docs/public/middleware/graph_full_no_mavlink.json +++ b/docs/public/middleware/graph_full_no_mavlink.json @@ -1 +1 @@ -{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#92d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#4dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d897", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#41d8cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d841d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#4d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8d241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#74d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#64d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41c5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#4162d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#6c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84167", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d8b341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#a141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#6cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d890", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d841b3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d84176", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d8415f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d84195", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d8418d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d85f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#41d862", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#4169d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#8341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d85041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d8ac41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#b8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#83d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#7441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#b841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d841ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84150", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#c8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#4197d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#4641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#46d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#6441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#d87641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#c841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#d86741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#41d869", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41d8c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d8d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#41cdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d89541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d88d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#4190d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#9241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#a1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#4188d8", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d89541", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#d86741", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d7d841", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#d85741", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#46d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#c8d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d7d841", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#c8d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d85041", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#4641d8", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#d87641", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#41d869", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41aed8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#41d869", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#c8d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d85041", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#41d85a", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#d88541", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#41d8ae", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#9ad841", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#d89541", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#d7d841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#64d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#d8c341", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#41d888", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#74d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#d841d2", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#d841ca", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d8ae", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#cfd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#a9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#a1d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#41bdd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#c041d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#9ad841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d88541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#9241d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#4143d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d84141", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#9a41d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41b6d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#b841d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#64d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#d8c341", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#41d888", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#74d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#d841ca", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#41aed8", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d841b3", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#4190d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#4dd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#4180d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d84185", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d84148", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#8341d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#41a7d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d86e41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#4dd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#4180d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d84195", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d84185", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#41d85a", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#4d41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#41d8c5", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#c841d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d841c3", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41a7d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d841bb", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#4dd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#4180d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#d88d41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d84185", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d8416e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#4641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#6441d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d8b341", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#41d8d4", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#8ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d84141", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d85741", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d85f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#cf41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d87e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d841ac", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#4188d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d8418d", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8417e", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41d84b", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d8415f", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#5d41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84150", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d8bb41", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#7b41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d89f", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d87e41", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d84157", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d8a441", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#83d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84150", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#41d843", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d84841", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d871", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#6cd841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#4171d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41c5d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8d241", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84150", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#4171d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#b8d841", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d841d2", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#41d8cd", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d741d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#4169d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#4179d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d4d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#41d862", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d8ae", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#4190d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#b1d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#a141d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#a941d8", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#5541d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#b841d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#4162d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#415ad8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d880", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#41b6d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#d841d2", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#4171d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#b141d8", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#92d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d879", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d89c41", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#41bdd8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#9ad841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d86e41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4152d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d897", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#4197d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#419fd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#b841d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d84176", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41b6d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6c41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#41d8a7", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d8ca41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#5dd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#55d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d890", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d871", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#6cd841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d8ac41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841a4", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8d241", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#64d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#d8c341", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#41d888", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#74d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#d841ca", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d8419c", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d88541", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d84150", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#41bdd8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#41d843", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#41d890", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#5541d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#d88d41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d8ca41", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d88541", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d8419c", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#4152d8", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#5dd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#d8419c", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#9a41d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#83d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#7441d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#4190d8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d87e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#7441d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#41d8c5", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#41d8d4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#d84150", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#d85741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#92d841", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#46d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d84150", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d7d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#83d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#41d8d4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#41d8b6", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#83d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#83d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#415ad8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#d87641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#41d8d4", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d89c41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#41d8a7", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d84150", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d88d41", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#41bdd8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d8ca41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d7d841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#9241d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d84841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#9a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#41bdd8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#83d841", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d87e41", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#5dd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#4171d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d8419c", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4152d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#d8ca41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#415ad8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#41d89f", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#5dd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#d84150", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#d8419c", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#d87641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#41bdd8", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84150", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#d89541", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#41d85a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#d88541", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#8341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d88541", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d84150", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#5dd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#5dd841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#41d862", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#64d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#d8c341", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#4169d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#41bdd8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#d88541", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#74d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d8ca41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#4162d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#41d862", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#8341d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#4190d8", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d841b3", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#4143d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#41d8a7", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#b1d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#41bdd8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#4641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d4d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41d84b", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#4162d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d89c41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#41d8a7", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#83d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d8ac41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#6c41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#55d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84150", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#c841d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#41d8cd", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841a4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d852", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d89f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84150", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#4179d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#7441d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#64d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#d8c341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#41bdd8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#d88541", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#74d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d88541", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d85041", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d84185", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d84148", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#d8ca41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#4152d8", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#9241d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#83d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#41d8b6", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#4171d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#9a41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d8419c", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#41d897", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#d8ca41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#7441d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d8ca41", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#41cdd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d89c41", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#a1d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d85741", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d87e41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d85f41", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#41bdd8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d84141", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d841d2", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d8bb41", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#b141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d8ca41", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84150", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#41d843", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#7441d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d8ca41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#8341d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8d241", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#41d8a7", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#cfd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d8ae", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#c8d841", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#b8d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#a141d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41d8c5", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#a9d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d8d4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41c5d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#41bdd8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#c041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#8ad841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#9ad841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#cf41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#83d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#7bd841", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41aed8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#4197d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d87e41", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#55d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d88541", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d8419c", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d8418d", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d89541", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d84176", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d89c41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d8415f", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d879", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#6441d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d8a441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d890", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84150", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#415ad8", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d4d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#d841bb", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#41bdd8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d8ac41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841a4", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#b8d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8d241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d88541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d89c41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d841a4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d852", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#7441d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#419fd8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#b841d8", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d89f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8d241", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d84157", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41b6d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#6c41d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#a9d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d4d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#41d869", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#55d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#8ad841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#b1d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d841c3", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d852", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d841a4", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#4188d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#d89c41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d84150", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#d8416e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#d84150", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#41d862", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#8341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#41bdd8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#4143d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#83d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d8b341", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#41a7d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84150", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#41d869", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41c5d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d89c41", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#4d41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41c5d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84150", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d8bd", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#b8d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84150", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#4162d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#415ad8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#41bdd8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#c041d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#9ad841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#6c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84150", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#8ad841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#c841d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#6441d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#7bd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#6cd841", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d88d41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8d241", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#64d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#d8c341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41c5d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#41d89f", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#41bdd8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#d88541", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#74d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#41d84b", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#41d862", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d8b341", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84150", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#8ad841", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8a741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d863", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#d841cc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d841a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#415bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#4163d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#7641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d89e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#419ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#76d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d8c541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#ced841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#41d896", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#4196d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#ce41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d84183", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#41d8ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84191", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#6fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#aad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#41d84d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d84f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#41d8a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#c741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#d8416d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d8cc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d841c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d84165", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d86d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d88341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#d8415e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d86541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#b8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#c7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#9bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d85b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#5241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d89141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#414dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#41a5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#41acd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#aa41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#41c2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#6f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#b841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d8414f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#52d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d8af41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d85e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d8c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#9b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d841d3", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#52d841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#b841d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#94d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d8bb", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#d8a041", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#4ad841", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d89141", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#41d8ca", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d8bb", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#94d841", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#d84174", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#d84174", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d89141", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8417b", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#7ed841", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#8cd841", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#41b4d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#41b4d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d84157", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d89141", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8417b", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#41cad8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#41d8d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d84f41", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d84f41", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d84f41", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d84f41", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d84f41", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#94d841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#d86d41", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#d841af", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#d84174", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#52d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41d8bb", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#d8d341", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#d84841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#41d896", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#68d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#d641d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#7641d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#c041d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#d8c541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#4196d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#6fd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#418fd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d86d41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841af", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d871", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#8c41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d8d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#a241d8", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d8c2", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#d8416d", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d854", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d8b641", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d854", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84191", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d887", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84191", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84191", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#5241d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#d8d341", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#d84841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#41d896", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#68d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#d641d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#d84157", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#41d8a5", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#415bd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8a741", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d8af41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d8bd41", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#41d84d", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#41cad8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d84141", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d84f41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#d86541", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#415bd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d841a7", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d8a741", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d8bd41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d8418a", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#94d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#41d8d1", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#aa41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84141", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d84f41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#41a5d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#415bd8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d8a741", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d8bd41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#6041d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#6f41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#d6d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d84174", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#41d8ac", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d8415e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#7ed841", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#94d841", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d8414f", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#41c2d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d85e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#4196d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d841d3", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d87441", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#59d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#4154d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d88341", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#4ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#414dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d89941", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d8b641", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#b8d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d84165", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#b1d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d879", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d87b41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#aad841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d85741", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#414dd8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d841a0", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#9bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d84183", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#9b41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#4145d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d84148", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#c741d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#4145d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d85b", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d86a", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#7e41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d89e", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#7641d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#85d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d89e", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#6841d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84191", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#a2d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#4180d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#b141d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d841bd", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#c0d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841af", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#41d8b4", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#41acd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d88f", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d8af41", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#416ad8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#419ed8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#4145d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#4341d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#9441d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#5241d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d84199", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#41d863", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#ced841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#d841cc", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#85d841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6841d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#85d841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6841d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d88a41", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#41d880", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#4a41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#4196d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d86d41", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#a241d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#4171d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#4163d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d841a7", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d845", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d841b6", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d1d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#76d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6841d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#85d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d89e", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#5241d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d8cc41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#5941d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#43d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#8541d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d841c5", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41bbd8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#c741d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#9441d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d89e", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d86a", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#d8d341", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#d84841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#41d896", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#68d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#d641d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#4187d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d8d8", "style": "dashed"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#c7d841", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#d8415e", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#d85741", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#43d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#d6d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d88a41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d8418a", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#4171d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#c7d841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d845", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d887", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#8541d8", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#b841d8", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#5941d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#41d879", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#41d845", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#41d887", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#8541d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#41d845", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d887", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#8541d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d8bb", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d8d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#4171d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#4196d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#a241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#4171d8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#414dd8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#6f41d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d8af41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#d8b641", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#4ad841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#c7d841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d845", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#41d8ca", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#9bd841", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d887", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#c7d841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#41d845", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#41d887", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#8541d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d8bb", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#9bd841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#94d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#9bd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#c7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#d8c541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#c7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#d8c541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#c7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#d8c541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#c7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d8c541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#c7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#d8c541", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#8541d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#94d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#a241d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#414dd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#4196d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d8cc41", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d6d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d8d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#a241d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#41b4d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#b141d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#4187d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d845", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#414dd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d841a0", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d8b641", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#5941d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#41d879", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#41d880", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d887", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#c7d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d8bb", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d8c2", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#a241d8", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#5941d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#b141d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#aad841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#41d845", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#d841a0", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#41d887", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#c7d841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#41d845", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#41d8c2", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#d841a0", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#41d887", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#8541d8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#a241d8", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#c7d841", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#52d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#41d8d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#d86541", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#41cad8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d845", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d887", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#8541d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#41a5d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#41d845", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#41d887", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41d8d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#c7d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#c7d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#5941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#5941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#5941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#5941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#5941d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#5941d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#c0d841", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#d8d341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#b1d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#aad841", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#d84841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#c741d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#ce41d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#7641d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#41d896", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#68d841", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#a241d8", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#416ad8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#aad841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d841cc", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d8cc41", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#4341d8", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#8c41d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#c0d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84141", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#41acd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d8cc41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d86541", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d8af41", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#60d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d8b641", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#ced841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#8541d8", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d8d8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#a241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#c7d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41bbd8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#b1d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#6841d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d88f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d8cc41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#4196d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#ced841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#41a5d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#aa41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#c7d841", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#a2d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#85d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#aad841", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#419ed8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#41d854", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d8cc41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d89e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#aad841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d89e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#a241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#4171d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84191", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d8cc41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d8b641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#c7d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#b1d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#aad841", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#d84841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#c741d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#ce41d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#41d896", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#68d841", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#4196d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d8d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d8bd41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d8418a", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#41d84d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#d8c541", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#c7d841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d845", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d887", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8bd41", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#4163d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#b141d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#41d845", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d887", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#4187d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#8541d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#4171d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#41d84d", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#415bd8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#d8416d", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#41c2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#a241d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d88a41", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#4ad841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d85e41", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#414dd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#4196d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#7641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d8b641", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d863", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#8541d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#8c41d8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#c7d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#4171d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d85741", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#4a41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#c7d841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#aa41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#41a5d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#4196d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#6fd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d86541", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d86d41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#418fd8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4187d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d841c5", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d87b41", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#4171d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#4154d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#52d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841af", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d841b6", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#43d841", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d89141", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#414dd8", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#d8a041", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d8b641", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#4a41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d86a", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d871", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d88f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d8cc41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#c7d841", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#8c41d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#b8d841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d84165", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#41d8b4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#9bd841", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d84157", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#94d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d8414f", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#9b41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#a241d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#c7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d8c541", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d88f", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#d8415e", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#aa41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d841af", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41bbd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d89e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#a241d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d86a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#a241d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#c741d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#b1d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#4196d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41d89e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#a241d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d841bd", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d8b641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#c7d841", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d84174", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#6841d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#76d841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d84183", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d86a", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#85d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#c7d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#aa41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841af", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#41d8b4", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d84f41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#aad841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#41a5d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d88f", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#6fd841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d8414f", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d841c5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#b1d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#aad841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#4196d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d8cc41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#8541d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#a241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41d89e", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d841d3", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#d84174", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#c7d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#4187d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#c0d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#41d8ac", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#9bd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#d86541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#a241d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#41b4d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d8c541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#c7d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#b1d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#4196d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d87441", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#4171d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#c7d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#414dd8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d8b641", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d8cc41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#c7d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#b1d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#a241d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#6841d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d8c541", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#418fd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d86d41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d8b641", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#ced841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d8d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d8af41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#6041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#aa41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#41a5d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d8414f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#aad841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#a241d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d6d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d86a", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#b1d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#aad841", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#d84841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#c741d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#ce41d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#41d896", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#68d841", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#41d8ac", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#c7d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d8414f", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v2.json b/docs/public/middleware/graph_px4_fmu-v2.json index 202abfcb01..86eeea468f 100644 --- a/docs/public/middleware/graph_px4_fmu-v2.json +++ b/docs/public/middleware/graph_px4_fmu-v2.json @@ -1 +1 @@ -{"nodes": [{"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d89f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d86041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d8c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#9f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d84b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d8414b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d8419f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d84160", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#9fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#4b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41c9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#4bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_board_adc", "target": "t_adc_report", "color": "#d841b4", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#5541d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d87f", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#d8416a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d894", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d87f41", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d894", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#d8416a", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d87f41", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#d841be", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#d841be", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#41d875", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#41d875", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#be41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41d860", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41bed8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#be41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41d860", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#9fd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#75d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41bed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d8c941", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#be41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d87541", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d89f41", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41bed8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#60d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8be41", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#a941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#9441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d84160", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#4b41d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d86041", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41d860", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d86a41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d84b41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841c9", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d3d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d8a9", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#41d8be", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d8417f", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d8414b", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#c9d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#8ad841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#416ad8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d8c9", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41c9d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#8a41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#8ad841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8be41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41a9d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d8419f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#94d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#4bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d84b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d85541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#418ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#417fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d87f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d8a941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#4160d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#4155d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#c9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d841be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#bed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#a9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#41d875", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d87f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d88a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d841a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#6041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#41d8b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#41d8be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d84194", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#75d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#60d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d84155", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d841a9", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d855", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d89441", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#416ad8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#c9d841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d841a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#9f41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#4194d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d85541", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#418ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#b441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8be41", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#b4d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#4141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#41d8b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d8c9", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#9441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41b4d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#55d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#419fd8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41a9d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#c941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#7f41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84175", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#4bd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841c9", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d89f", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#6a41d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d8d3", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d841b4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#be41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d894", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d894", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#7fd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41d860", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#8ad841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#94d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41d860", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#8ad841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d8be41", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d8c941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#94d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d8d3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8be41", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d841b4", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#9f41d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d84b", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#be41d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41d860", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8be41", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841c9", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d3d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d841be", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#4141d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#b4d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41d875", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d87f", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#9fd841", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d89f", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d8419f", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d8c9", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#6a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d3d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d84194", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#8a41d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d8417f", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#6ad841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41a9d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#419fd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d8414b", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d86a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41a9d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d87541", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d85541", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#7f41d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84175", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#4bd841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d88a", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8be41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#a9d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#4175d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d8418a", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8be41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d89f", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#c9d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d87541", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d841d3", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8be41", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d8419f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41a9d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#94d841", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d84b41", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d89f41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8be41", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d341", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#bed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#94d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#55d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#4bd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d87f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d88a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d89f", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d3d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41c9d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41b4d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#419fd8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#418ad8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#417fd8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#4175d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#4141d8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#4b41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#9441d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#9f41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#be41d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d84160", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d8414b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d87541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#416ad8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d8c9", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d87541", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#6ad841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d86041", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d8c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d87541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d8418a", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#41d8be", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d88a", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d8b441", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#418ad8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41b4d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d86a41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#b441d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d8c9", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41a9d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#75d841", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#6041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41d875", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84175", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d8417f", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d89f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841c9", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d84155", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d87541", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#6a41d8", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d84160", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#9fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41c9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#4b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8419f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d84b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d86041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#4bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#9f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d8414b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d89f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_board_adc", "target": "t_system_power", "color": "#d84141", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#41d86a", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#94d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d3d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d8414b", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#41d8b4", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d3d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41d8b4", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d8414b", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#bed841", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#d84155", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#d84155", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#bed841", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#d8be41", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d8be41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#4194d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d86041", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d8b441", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d841b4", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#4194d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#417fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#4175d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#9f41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d86041", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#6041d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d841b4", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#be41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d8b441", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#41d89f", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d87f", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#6041d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#4bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#4160d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#9441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#75d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#417fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d841c9", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#4175d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d86041", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#6041d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d841b4", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#be41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41c9d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#7541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#6a41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d894", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d84b", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d86a41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4194d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d88a41", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8419f", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d841d3", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#41b4d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#418ad8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#417fd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d89f41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8c941", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#c9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#b4d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d8416a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#9fd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#8ad841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#7fd841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d84194", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d341d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d8a9", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8c9", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#417fd8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d3d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#9441d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d89441", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#5541d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#be41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d341d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#a941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d84b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#b441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#60d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#94d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#55d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d87541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#be41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#4bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d841d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d87f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d855", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#41b4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d860", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d841c9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#417fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d841be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d8a941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#416ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d87f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d841a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d8be41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d84194", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#4155d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d88a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#4b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#4141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#6041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#bed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#8a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8417f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d8416a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#a9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d84155", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41d8d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d8414b", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#b441d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d84194", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#4155d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d84175", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#c941d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#7fd841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#b441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d84b41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#be41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41bed8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#419fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#417fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d841be", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#41d875", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#414bd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#4b41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d8418a", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#7541d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d8a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#9441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8be", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d8416a", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d84160", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#a941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d85541", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#41a9d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#418ad8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d8d341", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d8a941", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41d8d3", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#6041d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#41d86a", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d86041", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d3d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d3d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#4175d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d88a41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#4194d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d86041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#5541d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#be41d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d88a41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#9441d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#4194d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d86041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#5541d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#be41d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#d341d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#41d89f", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#9441d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#41d86a", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d86041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#be41d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41c9d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#4bd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#41b4d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d8414b", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#419fd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#417fd8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d89441", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d841c9", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d89f41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d8a941", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#418ad8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d8be41", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d88a", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#c9d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#bed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#5541d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8417f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#9441d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8be", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#b4d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d8416a", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#9f41d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#9fd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d84155", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8c9", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#94d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#9441d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d84b", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#75d841", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d84b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#9441d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d85541", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#41a9d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#60d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d8d341", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#418ad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#416ad8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41d8d3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d8a9", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#4155d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#9441d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#41b4d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#9441d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d84175", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#418ad8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d8416a", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d84160", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d86041", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#9441d8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#4141d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#be41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#4bd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#a941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#5541d8", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#9441d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d86041", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d89f41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8c941", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d8d341", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d3d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#c9d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#b4d841", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#a9d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#94d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#55d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#4bd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d860", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d8414b", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d87f", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41d8b4", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8be", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41d8d3", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#41b4d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#419fd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#418ad8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#417fd8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#414bd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#4b41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#5541d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#9441d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d841d3", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d841be", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8419f", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d84160", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#4155d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#9441d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#41b4d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#b441d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d86a41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#5541d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#4bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#41b4d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8419f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d8416a", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#4b41d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d89f41", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#60d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#be41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#7541d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#41d875", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d8a9", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41bed8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#a941d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d87f", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d87f41", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#41d86a", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#418ad8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d8d341", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d8a941", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#c9d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#bed841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#7f41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d8be41", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v4.json b/docs/public/middleware/graph_px4_fmu-v4.json index 3c4197a667..2f2a7e7b5e 100644 --- a/docs/public/middleware/graph_px4_fmu-v4.json +++ b/docs/public/middleware/graph_px4_fmu-v4.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#d84147", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#6741d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d84147", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#41c4d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#41c4d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#4194d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4194d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#53d841", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d89b", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d841c8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#419bd8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d4d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d4d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41d8d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#59d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d841cf", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d88e", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d8cf41", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8a641", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d8414e", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41d8cb", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d8d1", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d1d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#4187d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d85c41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#9741d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#9dd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#b941d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#75d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#53d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d86241", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d841b4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d87741", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#4157d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d8c241", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d88e", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41a9d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d441d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#a441d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88b41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#41afd8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#41a9d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#41d85e", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#d84e41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#8241d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#c641d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#b9d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#4541d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#9041d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#4541d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d85e", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4179d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#4165d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#4cd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#7541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d85541", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#4143d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d84169", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d87041", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#d84192", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#ab41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d84141", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#4157d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#a4d841", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#bfd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8a641", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41a9d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d8b6", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#b241d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d8b441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#89d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#cd41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#41b6d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d87e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#418ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d841a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d841a0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d84199", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#d89241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#d84192", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d857", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8a041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d84177", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d84170", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#414ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d8bb41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#5941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#5341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#4c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8c841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#41d879", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#7541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#b2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d89b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8a2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#9741d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88b41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d841c2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d441d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d8af", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d86941", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#90d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#89d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#7bd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41bdd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d87041", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#4187d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d841a6", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d88441", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d850", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#416cd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8a641", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d872", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d84162", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#7b41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#8941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8a2", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#b241d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41afd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4172d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#41a2d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841ad", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d8417e", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d84170", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#53d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d841d6", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d8415c", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#45d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#41d84a", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#9d41d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#82d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#41d887", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#97d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d8c4", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#41d843", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d84170", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#abd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#41d8a9", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#6ed841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#cdd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#6041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84155", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d85e", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8418b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#67d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#4541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d865", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d8ad41", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#4180d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d880", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#6e41d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#cdd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d8a641", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#7bd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#41d84a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d89941", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d89941", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4150d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#4180d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#4180d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#4180d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#4180d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d8a641", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#9041d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d88e", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d88e", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#7b41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d84199", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#c6d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d84170", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#4187d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#a441d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#9dd841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d87041", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41a9d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#418ed8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#4187d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#41d84a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d89941", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d8a641", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d8ad41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d8b441", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#4c41d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d8d641", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#41d880", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#cdd841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d87041", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d841bb", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#bf41d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d88e", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d84170", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#9041d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8a641", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#9041d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#7b41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d88e", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#41c4d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#97d841", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d8b6", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#ab41d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d8bd", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#82d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#6ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#53d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d86241", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d841cf", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#41a2d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d87041", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d841bb", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d841b4", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d87741", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41d843", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#4187d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d84199", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d850", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d857", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8a641", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d8417e", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4150d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d8b441", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d865", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8c841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d872", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#6741d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#6e41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d8415c", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d88e", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#9741d8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#a4d841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8a641", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d85e", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d1d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#67d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#4541d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d85c41", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8a2", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#d84192", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d841cf", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d87041", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841ad", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#cdd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#c641d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#5341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d8a641", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#c6d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#9041d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8a641", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d8414e", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#cdd841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d1d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d87041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8a641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#d87041", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d84199", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d87041", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#b941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41bdd8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#7b41d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d87e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d88e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d8b441", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8a641", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41d843", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#6ed841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8a641", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d8bd", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#bf41d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d1d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#53d841", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d89b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#d84192", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d87041", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#5341d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#41d84a", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d8b441", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#5941d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8a641", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d8b6", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88b41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8a641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d8cf41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#cdd841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#97d841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#59d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#41d879", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d88e", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d8d1", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41bdd8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41afd8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#41a2d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#419bd8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#4143d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#8941d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#8241d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#9741d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#ab41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d841b4", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d841a6", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d84199", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d8418b", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d84177", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d84170", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d84169", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d87041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88b41", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84155", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d87041", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d87041", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#b941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#d84192", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84141", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41afd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8a641", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d87041", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#90d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#89d841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#cdd841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#75d841", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#b9d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#4187d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d841a6", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d88441", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#419bd8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#cd41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d8418b", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#7b41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#41a2d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d8bd", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#82d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41d843", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#6ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d841a0", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d8415c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#a441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#cdd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d8a9", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d841d6", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#cdd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#82d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d8418b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d88e", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#415ed8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#60d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d87041", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8a641", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d84184", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#cdd841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d88e", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#a5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d841d7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#84d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#9ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#41d873", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#4173d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#41ced8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#a541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#418dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d8ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d8d741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#41d886", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#4186d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#9e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#8441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41d88d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#419ad8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#419ad8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#7ed841", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#41d886", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#41d886", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#91d841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#91d841", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#91d841", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#b941d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#50d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#41d5d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#c6d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d8d741", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#d8418f", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#4159d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#c641d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#d8418f", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#c641d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#4159d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#4341d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#d86841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#c641d8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#d8415b", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#4145d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#4145d8", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#4145d8", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#4145d8", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#4145d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#b941d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#50d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#c6d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d8d741", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d89641", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#b941d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#50d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#c6d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d8d741", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#77d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#8441d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#41b4d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#41d5d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#77d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#b941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#50d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#41ced8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#41d5d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d8414e", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#8441d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#77d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#c6d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d8d741", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#41b4d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#98d841", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#8b41d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#4180d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#63d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#4186d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d84e41", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#50d841", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#8441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#4173d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#c6d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#84d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41d88d", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#4166d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#77d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#415fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41aed8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d8d741", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41bbd8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d8bd41", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#7141d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#bf41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d86841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d86e41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#5dd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#41d859", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84196", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#4341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d89a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#8b41d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#77d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#8441d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#41a7d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#b2d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#4193d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#d8a341", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#41c8d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d84161", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#d8419c", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#d841bd", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#d87b41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#56d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#4941d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#d8c441", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#d841b0", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#4152d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#b2d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d841b0", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#d8b041", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41d8d5", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d88941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d841d7", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#b241d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d841a3", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d84147", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d8ae", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#416cd8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#5641d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#5dd841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#41d89a", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#4341d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#9e41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d8d141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84168", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d84741", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#4186d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d86c", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41c1d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#b9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#b2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d8ce", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#9ed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#91d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#8bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d841d7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#77d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d841d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#41a1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#d87541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#49d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d841a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d88f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#4159d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#4145d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d85f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#5041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d84182", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41d88d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d8417b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#bfd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#d3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#ccd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d893", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d8415b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#7741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#7e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d89a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#8b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d8b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41d8bb", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#b2d841", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#41a7d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d8416e", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d85441", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#b2d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84141", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d841d1", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41aed8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#71d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#418dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#4186d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d84b", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d866", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d85f", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d84189", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#7741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d89a", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#41d8a7", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d8ae", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d8c1", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41c1d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d85b41", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#41d873", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d88241", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#41d8a1", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#91d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d84175", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d88f41", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#a541d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#6341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d86841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#b941d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#abd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#50d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#c6d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d8d741", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#41d8c8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#c641d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8b641", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#a5d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#41d879", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d88f41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d86141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d845", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d8a941", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d841ca", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d841c4", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#8441d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d873", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d88241", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#6a41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d88241", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d873", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#9141d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#9841d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d841b0", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#50d841", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#8441d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#77d841", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#c641d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d841b6", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#c6d841", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#4186d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#d8b041", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#4193d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#d84741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d86c", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#50d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d8bd41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d8d741", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#4159d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#4159d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#d841ca", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#8441d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#8441d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#8441d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#8441d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#d8b041", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#4193d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d86c", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#50d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d8bd41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d8d741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#4186d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#41c8d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#d8b041", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#4193d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d86c", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#50d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d8bd41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d8d741", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d341d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d89c41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#c6d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d841b6", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d89c41", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#41d5d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d88f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d89c41", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#41aed8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#77d841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#b9d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d341d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#77d841", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41aed8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#d87541", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#4186d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#50d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d841b6", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#4159d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#d8b041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d86c", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d8bd41", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#5041d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d8d741", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#8441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#41d8ae", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#c6d841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#4186d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#bf41d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d88241", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#56d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d841b6", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#41c8d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41d8ae", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d88f41", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d8a341", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#8b41d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#49d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d841a9", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#4186d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#41c8d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d89a", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#41d886", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#8b41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d841d7", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d8c8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d8ce", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#bf41d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41d5d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#98d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#c641d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#91d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41c1d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d341d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#7ed841", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#41b4d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41aed8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d841ca", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d86841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d86e41", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d841c4", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#418dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d841b6", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#4166d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89c41", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d845", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d84b", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#41d859", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84196", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#4341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d86c", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41d879", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#5641d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41d88d", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d8417b", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d84175", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#5d41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d8d741", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#6a41d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#8b41d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d8ae", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#9e41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#a541d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d88241", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#41d873", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#9841d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41c1d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#4173d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d841b0", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d85f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#4186d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#56d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d86841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#98d841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d8ae", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#416cd8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d88f41", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#6341d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d845", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#4186d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#41c8d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#4186d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d341d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89c41", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#415fd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d341d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d852", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#4186d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d852", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#4186d8", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d84161", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#63d841", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#4186d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d841b6", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#4941d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#4152d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#41d89a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#8b41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d341d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#71d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#4186d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d86c", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41bbd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d89a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d86c", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#9ed841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41d8ae", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d341d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d841d7", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#71d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d841c4", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#4186d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d88241", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#56d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d89a", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d841b6", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#a541d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d8416e", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#71d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#8b41d8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d8415b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#8b41d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d841b6", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#41d8ae", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#49d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#416cd8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#4186d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d341d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#4186d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#5d41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41c1d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d86c", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#4186d8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d86841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d88241", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d88941", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89c41", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d8a341", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d8b641", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d8d141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#a5d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#98d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#91d841", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#84d841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#8bd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#71d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#5dd841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d852", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#41d859", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#41d886", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41d88d", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d8ae", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d8b4", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d8c8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41d8d5", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#41ced8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41c1d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#41a1d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#4180d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#418dd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#4186d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#415fd8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#4159d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#4341d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#7141d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#7741d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#a541d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#b241d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#c641d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d841d7", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d841d1", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d841b6", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d841a3", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d8419c", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84196", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#d8418f", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d84182", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d8414e", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#4186d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d852", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#4186d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d873", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#63d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#4186d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d86c", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41bbd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89c41", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#7141d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84196", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d89a", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d84189", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d8ae", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d341d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d85b41", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d841d1", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#414bd8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41aed8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41c1d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#bfd841", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#41d89a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41d852", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#71d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d841c4", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#63d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d86841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41d879", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#91d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#a541d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#6341d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#41d859", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d841ca", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#d8b041", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#4193d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d84741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d86c", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#50d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d8bd41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d8d741", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d8a941", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#b941d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#abd841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#41d8c8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d341d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#5d41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41d852", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#6a41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d341d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41aed8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#71d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d8a341", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d880", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d3d841", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#ccd841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41d8ae", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v5.json b/docs/public/middleware/graph_px4_fmu-v5.json index 3177688f80..b63dd33682 100644 --- a/docs/public/middleware/graph_px4_fmu-v5.json +++ b/docs/public/middleware/graph_px4_fmu-v5.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#b5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#8641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d8ac41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84176", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d87b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#4181d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d895", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#4174d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#a741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d841ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#419cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d8c641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#5741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d8a541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#57d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41d881", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d841b9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41d8b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41a3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8d441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#414cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d84191", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#d88341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d89e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#c241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#bbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#41d86d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41d2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#6b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41b0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d841cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d8417d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d8cd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41b7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#b541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#d87d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#5ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d89c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41d8b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4195d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41d84c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#41d8d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d841d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8419e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d84198", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d89141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d8b941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#a0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#86d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d841c0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#a7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#64d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#5e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#6441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#a041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d89841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#72d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#6bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#417bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#78d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#bb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d8416f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d86f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d87641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#c2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d84183", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8c041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#416dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d841c6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#7841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d874", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d841a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#7241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#c9d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d8414e", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#c9d841", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d84169", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d84169", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4145d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#5e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d841b2", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#d87d41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#4341d8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#41d845", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#72d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#78d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#72d841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#d88341", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#8c41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#72d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#b541d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41cbd8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#a041d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d84e41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#7241d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d88a41", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#bbd841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d86941", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d89841", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d8418a", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d841ac", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#6bd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41d2d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41d8b7", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d84198", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41d84c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d866", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d89e41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d8b241", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8419e", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d8c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#7f41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84162", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41cbd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#9341d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#4159d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d8417d", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d8416f", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41b7d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4181d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d895", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#41d8cb", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#bb41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#d8416f", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#d841cd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d84191", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#d8ac41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d8cb", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#5ed841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d89c", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#ae41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d8c641", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#86d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#5741d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#4174d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d859", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41b0d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d874", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#417bd8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#c2d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#64d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8d441", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d8416f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d86941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41b0d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#50d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#43d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#49d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#c241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#41a9d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d86241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#419cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41d852", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d860", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d87641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d8a541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d841b9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#4174d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d87b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8c041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d841b2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d8b941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d841a5", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#4152d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#4341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4145d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d8417d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#6441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#6b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#41d8d2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#a0d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#7241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#7841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84162", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#d8415b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#9341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41bdd8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4181d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d895", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#a7d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#4159d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d8417d", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#cfd841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d88f", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#49d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#c941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#cf41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d86941", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4195d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d859", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d841d4", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#416dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41d881", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d841a5", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d6d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8a3", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#8641d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#9341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#6bd841", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8d441", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#414cd8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d8cd41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#4160d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#7841d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d866", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d841c0", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#93d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84155", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#41d86d", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d84147", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#9a41d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d86f41", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4145d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d841c6", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#a741d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#7841d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d89141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#4188d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#b5d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#418fd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#8cd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84176", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41d8b0", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#414cd8", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d8cb", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d8d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#414cd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41a3d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d888", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d85541", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d84183", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#9ad841", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d85b41", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#8641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d86941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#9a41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d841b2", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#418fd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d84183", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#d84183", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#6441d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#43d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#9341d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#6bd841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d86941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#9a41d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#86d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#9a41d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#6441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#6441d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d86941", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41cbd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#6441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#6441d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#7841d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#4941d8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#6bd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#9ad841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d85b41", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#41d859", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d841b9", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#86d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d841b2", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d84183", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#6b41d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#41d2d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84162", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#9ad841", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#d8415b", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#9a41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#6bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41d859", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#7841d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#414cd8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41cbd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41d84c", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#4152d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84162", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d841c0", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#41d852", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d84191", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#c9d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41cbd8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#9341d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#4174d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#64d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#b541d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#41d845", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d85b41", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#c941d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d86941", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4195d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d86f41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d859", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d860", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d841d4", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d841c6", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#418fd8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d89141", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d89e41", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d874", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#417bd8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d888", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d8cd41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#4160d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8d441", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8a3", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41d8b0", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4145d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#6bd841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#4941d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d8c4", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#6441d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d8d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#7241d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#93d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#9a41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#9341d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#72d841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d8cb", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8d441", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#414cd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#5041d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41a3d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d86941", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8a9", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d8cd41", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41b0d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d859", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#7841d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#b541d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d641d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d89141", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d841c0", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41d852", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d86941", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d84191", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#4941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#6441d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d88a41", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d874", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#57d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#a7d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#4181d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d86941", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#9341d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#41d881", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#b541d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41d8b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41cbd8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d8a541", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#419cd8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#cf41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#4174d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#9341d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d87b", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41d881", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#418fd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41d8b0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d86941", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d8417d", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#a7d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#9341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#414cd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#93d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41cbd8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84162", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#6441d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d84141", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d8b941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d86941", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d841c6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d86941", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#64d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8d441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d86f41", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d87641", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#d87d41", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#d88341", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d89141", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d89841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d8a541", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d8b241", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8c041", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d8c641", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d8d441", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#c2d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#bbd841", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#a0d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#93d841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#6bd841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#5ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#57d841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#50d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#49d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41d84c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d859", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#41d86d", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d874", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d895", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d89c", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8a3", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41d8b0", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41cbd8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41b0d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4195d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#4188d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#4181d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#4174d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#414cd8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4145d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#4941d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#5e41d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#5741d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#6441d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#7241d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#7841d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#7f41d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#9341d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#a741d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#ae41d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#bb41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#b541d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d641d8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d841cd", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d841c6", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d841ac", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d841b2", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d841a5", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8419e", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d84198", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d84176", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d84169", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84155", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#4181d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#cfd841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#4159d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d88f", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#6441d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41d8b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d86941", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d841a5", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d859", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d6d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#49d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41b0d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84162", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#6bd841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d84198", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d8ac41", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#9341d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#416dd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d86941", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8d441", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#41d8d2", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#43d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#57d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#9341d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41d881", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#4160d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d866", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#c9d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d841c6", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#418fd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#93d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41d8b0", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84155", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d86241", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d84141", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d8416f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#41d2d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#86d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#9a41d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84176", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#a741d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#b5d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#41d86d", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d84147", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d86f41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d841c6", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#418fd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d8417d", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d888", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#64d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d86941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41d859", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d895", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#bbd841", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#aed841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41cbd8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#6bd841", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#4161d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#c841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d8ae41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d8b541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#9bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d867", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#4174d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#6141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d85a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#c2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#414dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#54d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d8c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#41a8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#bbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#88d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#4181d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#8841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#c8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#8ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#47d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d881", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#5a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#d8a841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41cfd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#416ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#4147d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#5441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#b541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#bb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d8419b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#a141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#41d84d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#9b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d84167", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#41c2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#4741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d8418e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#a8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#a1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d8b5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d8414d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d8d541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#61d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#5ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#41d86e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#41d874", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d84d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d88841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d87b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#c241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#4dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#41b5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#4d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#a841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#d841d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d841ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d841a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d8415a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d88e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d847", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#8e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#74d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#7441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#8141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d86741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d89b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#b5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41d861", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#41d8a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#417bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d84188", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d8cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d841b5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#81d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#4167d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#d84188", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d86e41", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d84188", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d841a8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#41b5d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#41b5d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#b541d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#b541d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#b541d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d8c841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#61d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#41c8d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#cfd841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d8c241", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#d841d5", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#417bd8", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#aed841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41bbd8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#41a1d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#41a1d8", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#41a1d8", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#41a1d8", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#41a1d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d8c841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#61d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#41c8d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d841a8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#ae41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d8c841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#61d841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41c8d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d84194", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d8c841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#61d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d8cf", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d5d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41c8d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#7b41d8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d8cf", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d8cf", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d8cf", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d8cf", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d8cf", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d5d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#7b41d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d841a8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#cfd841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d8c841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#61d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d5d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d84161", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#41c8d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#cfd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#d8a841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#7b41d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d8cf41", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d87b41", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d841a8", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d841ae", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d847", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d8c841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d854", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d8418e", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#a141d8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d5d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#9441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#4dd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d841c2", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d85a41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41d894", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#8841d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41c8d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41aed8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#41d86e", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41cfd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d86141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d87b41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#41d874", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#416ed8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d881", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#4167d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d8d541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d8417b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#88d841", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d841a8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d5d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#41d84d", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#8141d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#4147d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d841a1", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#cf41d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#b5d841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#94d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#a8d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#41d89b", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#9b41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#6141d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#4154d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#d85441", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#c8d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d8ae41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#d8b541", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#4d41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#7441d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#8141d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d87441", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#4147d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#a8d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#4d41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#a1d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d8c2", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d8419b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d841c8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4141d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d8414d", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#4174d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#bb41d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8bb", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d888", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d541d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#8e41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#8ed841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d8416e", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#4dd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d84154", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#8141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#6ed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d8c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d8cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41d8d5", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#5ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41bbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#b541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d86741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#41a1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d87b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d88841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d88e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41d85a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#c241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d867", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d841b5", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8a141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#4181d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#4174d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#416ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d881", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d841a8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d8c241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#415ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#414dd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d5d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#c2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#4147d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#bbd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#4741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#41d8a1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#5441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#5a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#81d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#417bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8bb", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#4147d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#cf41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#41d84d", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d84167", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d8415a", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d5d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d87441", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#4147d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#41a8d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#a841d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#4dd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#bb41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d847", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#c841d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#419bd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d841bb", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#418ed8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d87b", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d881", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d88e", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#4741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d8b5", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#81d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#6741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#7bd841", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d84154", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8bb41", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#54d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d5d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#47d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#41d8a8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#67d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#41c2d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d841b5", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#b541d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d8417b", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d8c841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#61d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#41c8d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d89b41", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#417bd8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d89441", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#9bd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d88141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#41d861", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d841cf", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#4161d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d841b5", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#6e41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d84147", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d84181", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d5d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8bb41", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#47d841", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d5d841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d84d41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#a8d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8bb41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#47d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d84174", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d5d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#4194d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#4d41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#4188d8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#41d8ae", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d5d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#74d841", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d84188", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d84d41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d8c841", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#4dd841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d841a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#8ed841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#41c8d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d84d41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#41aed8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4141d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#8141d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#6e41d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d5d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d5d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d5d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d5d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#416ed8", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#d841a8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d881", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d841a8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d847", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d8cf41", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d8cf", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#4dd841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#d841a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#8ed841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#41c8d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d84d41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#41aed8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4141d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#4dd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#94d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d841a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#8ed841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41c8d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d84d41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41aed8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4141d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#8141d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#d841a1", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d84194", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#8ed841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41c8d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#4dd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41aed8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#4141d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#8141d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d841a8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#4dd841", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d841a8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d841a8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d87b41", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d84188", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#4dd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d87b41", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d841a8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#41d881", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d841a8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#4dd841", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d841a8", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#41d847", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#cfd841", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d841b5", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#74d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#74d841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41d8d5", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d5d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#41c8d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#4dd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#41aed8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#bb41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d847", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41d85a", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#4181d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#416ed8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d841a1", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d8c241", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d8c841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#bbd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4141d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#8ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#41d8ae", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d87b41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#94d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d8d541", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#88d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#4dd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#c8d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d841b5", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#b5d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d87b41", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#67d841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#5441d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#5a41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#4dd841", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d84188", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#4174d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#41b5d8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#8e41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d8c8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d84154", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41cfd8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#a841d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41c8d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#4dd841", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#ae41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#41c2d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#b541d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d86141", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d847", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d88141", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41d861", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d89441", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d89b41", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8a141", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d87b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d881", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d841a8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d888", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d8cf41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d8c841", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d8418e", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d8d541", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#4167d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#cfd841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d84181", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d84174", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#8ed841", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d8416e", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#88d841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d8b5", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#6e41d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#417bd8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#47d841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#4dd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d84154", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#4d41d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#4188d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#41d8a8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d8417b", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d88141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d8cf41", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#67d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#5a41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#41c2d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#bb41d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d841b5", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#c8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d84d41", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#4dd841", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#cfd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#94d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d841a8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#4dd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#a141d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d8415a", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d5d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#8ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d8cf41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#cf41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#a141d8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d5d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#4dd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#8ed841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d8cf41", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d89b", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#4167d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#a141d8", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#6141d8", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#4dd841", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d8ae41", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#4d41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d87b41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#8ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d8cf41", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#4167d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#a141d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#4dd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#7bd841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#8841d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d841a8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#8ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d8cf41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#6ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#8ed841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d867", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#419bd8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#bb41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#4174d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d84181", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#4dd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d881", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d8cf41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#a141d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d84167", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d8415a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#4dd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#c8d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#7bd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d87b41", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41bbd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d841a8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#8ed841", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d88841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#4dd841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#4dd841", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d8416e", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d84154", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#8ed841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d84d41", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d85a41", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d88141", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d88e41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d89441", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d89b41", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d8bb41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d8c241", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d8c841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d8d541", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d8cf41", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d5d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#cfd841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#b5d841", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#aed841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#9bd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#8ed841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#88d841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#81d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#7bd841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#61d841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#54d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d847", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#41d874", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#41d86e", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d87b", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d881", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d888", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#41d8a8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d8b5", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8bb", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d8c2", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d8cf", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#41b5d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#4174d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#416ed8", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#4167d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#4161d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#4147d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#4741d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#7441d8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#9441d8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#9b41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#a141d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d84154", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#a841d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#bb41d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#c241d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#cf41d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d541d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#d841d5", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d841c2", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d841b5", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d841ae", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d841a8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d8419b", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d84181", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d84174", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d84161", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#417bd8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d8414d", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#8ed841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#cf41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d5d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#47d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#8ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#4dd841", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#41a8d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#41d84d", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#a141d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#bb41d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#8841d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d841a8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#8ed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d881", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8bb", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d847", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#4167d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#54d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#4dd841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#81d841", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d841bb", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#418ed8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d8b541", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#41d86e", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#4741d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#bb41d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#5ad841", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d8cf", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#8ed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#a141d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d5d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#41d8a8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d8417b", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d84181", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#a141d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d84188", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d89441", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#6e41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#b541d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d86141", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#41a1d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d841a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#8ed841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#41c8d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d84d41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#41aed8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4141d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#61d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d84741", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d84d41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d89441", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d89b41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#8ed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d5d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#a141d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d84174", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d84d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#4dd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d87b41", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d847", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#416ed8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d8cf41", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#414dd8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#c2d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#b5d841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d8416e", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#7bd841", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v5x.json b/docs/public/middleware/graph_px4_fmu-v5x.json index 95dd212785..e356726e0b 100644 --- a/docs/public/middleware/graph_px4_fmu-v5x.json +++ b/docs/public/middleware/graph_px4_fmu-v5x.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#d84177", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d8415c", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d84177", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#c641d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#c641d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#abd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4cd841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#97d841", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d8bb41", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d84155", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d8bb41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#abd841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d8bb41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#bf41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#418ed8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#abd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#5941d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#9741d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d841bb", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#90d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41bdd8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41a9d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d88441", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#4541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#5341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d8d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#ab41d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#59d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d86941", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#75d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#67d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d850", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d84199", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8417e", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d84170", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#b2d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d84147", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#41d1d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#bfd841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841a6", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d879", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4187d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#bfd841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#89d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#b9d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d865", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#419bd8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#d8d641", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#41d8d1", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#d841a0", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d8af", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41afd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#cd41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#9041d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d880", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41d89b", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#4157d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#d88b41", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d4d841", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41d8cb", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d84192", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#6741d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#bfd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41a2d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d841c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#97d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#b941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#75d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d841d6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#6ed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41a9d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#4180d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#53d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#4165d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#415ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d850", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d87741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d87e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d85e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d86c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d872", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#d88b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#414ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#4c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d89941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#4143d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d8a641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8c841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d8c241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#8941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#c6d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d8a2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d84169", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#a441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#a4d841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4187d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41d843", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#b9d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d841b4", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d872", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841a6", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#6041d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84162", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#b941d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d841cf", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d86241", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d841c2", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d841bb", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#4157d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#4150d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d89241", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#4143d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8b441", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d887", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#cdd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d8b6", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41c4d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d841c8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41d88e", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d85541", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#45d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4194d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d8a041", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d84170", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#4172d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84e41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#41b6d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d8cf41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#8241d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#7b41d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4cd841", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#41d84a", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#7541d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#41d857", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41d88e", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#7bd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d841ad", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#41cbd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#9d41d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d894", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#416cd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#82d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d872", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#60d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#b241d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d8ad41", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d87041", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d8414e", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8418b", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#75d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d8b441", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d86241", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41c4d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84e41", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#bfd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d879", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d89941", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#41cbd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d8414e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d8414e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d8414e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d8b441", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d850", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d87741", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d85e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#cdd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#41d8d1", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41c4d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84e41", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#bfd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d87041", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41c4d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#bfd841", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d84155", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d879", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d850", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41d894", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d84177", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#cdd841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d841bb", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d87741", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#41d88e", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#abd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8418b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84e41", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#75d841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d841d6", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#6ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d87041", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#4157d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d89941", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d8a641", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#6741d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d8418b", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41d894", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d8af", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#bfd841", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#a441d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#ab41d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#82d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41d88e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#75d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#67d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#41d8d1", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d84147", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#41d8d1", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d84177", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#c641d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d850", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84e41", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#a4d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#75d841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41a9d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41a2d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#67d841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4cd841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#45d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d841c8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#4172d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#415ed8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d841bb", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d850", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#4157d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d841ad", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#5341d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#5941d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#6741d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d8bb41", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d887", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d84199", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d84192", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#cdd841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d84170", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d8415c", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d8b6", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#b2d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8b441", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#416cd8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#82d841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d85c41", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d88441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#b241d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d841c8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d85541", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41d88e", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#d88b41", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4194d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d841ad", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#5941d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#d841a0", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d84170", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d8b441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#41d8d1", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8b441", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#90d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d87741", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d894", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d894", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d872", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#6741d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#75d841", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#b2d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#d841b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#cdd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#6041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#4541d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#59d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#5941d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d8a2", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#4157d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#cdd841", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#4c41d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d894", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8b441", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#7bd841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#9d41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#41cbd8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8b441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#75d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d841b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#cdd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#5941d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#d841a0", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d84170", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#45d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#75d841", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#97d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d850", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8b441", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d8c241", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8b441", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#41d84a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8b441", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41a2d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d89241", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#d88b41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d8cf41", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d8d641", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#cdd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#b9d841", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#9dd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#90d841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#41d857", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d85e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41d89b", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d8a2", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d8b6", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41bdd8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41afd8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#419bd8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#418ed8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#4541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#6041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#9041d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#9741d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#c641d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d441d8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#cd41d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8417e", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d84170", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d872", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#4157d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#75d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#6041d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#6741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8b441", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d87741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#4157d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8b441", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d86941", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d841bb", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#4157d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#89d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d441d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#75d841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#b2d841", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d8c4", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#4150d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#d88b41", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#cdd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#41d894", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#414ad8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d85e", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d841c8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#41d1d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d84169", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d85541", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#4541d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d8a041", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d84170", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#41cbd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d87041", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d8af", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41c4d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84e41", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#bfd841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d894", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d857", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d84184", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#41b6d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d8cf41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#7bd841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d8ad41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41a2d8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#4179d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#4157d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d86c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d89241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#4541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#b9d841", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#41d2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#7c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#4ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#4196d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#4189d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#c441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d89d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#d8b141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#41d862", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d8b1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#4168d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#96d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#6f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#a341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41d8b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#41aad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#419dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8416f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#aad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#5bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#54d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#47d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#41d8a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d84190", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#7cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d87c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d841b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#cbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#b7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#62d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41d8aa", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#4190d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#6241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#cb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#41b1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#5441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#9641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d841d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d8417c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#417cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d86f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d86f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#416fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#4741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d87c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d8cb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d85b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d868", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d896", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#415bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#4e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d841b1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d8419d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#c4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41d882", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41d890", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41a3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#4162d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d841cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d89041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#a3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#41b7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#4182d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8aa41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41d8d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#5b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d8b741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8d241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#6fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d889", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d89d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#41d847", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#4147d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#b741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d841aa", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#aa41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#68d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41d8d2", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#68d841", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#41d889", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d889", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#4162d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#4162d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#6841d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#6841d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#6841d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d241d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#bed841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d86241", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#b741d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#416fd8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41d882", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d86841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d8cb41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#41d889", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#4182d8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#6241d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#6241d8", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#6241d8", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#6241d8", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#6241d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d241d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#bed841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d86241", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#416fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#41d8c4", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#bed841", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#41d854", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d8c441", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d86241", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#b141d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#416fd8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#b141d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#b141d8", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#b141d8", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#b141d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#b141d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#41d854", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d8c441", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#b741d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#b741d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#bed841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#41d854", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d8c441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d86241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#90d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#416fd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#419dd8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d841d2", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#41d875", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d88941", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#bed841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d8c441", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d89041", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#a3d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d86241", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d841cb", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#54d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d8417c", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41bed8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#be41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d8d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d241d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41d8aa", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d87541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#7cd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d8cb", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#a341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d88241", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d841b7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#47d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#4741d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#cbd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d8415b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#7541d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d8c441", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#4190d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d87c", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#8241d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#c441d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#41d8a3", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#d841a3", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#4196d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#d84196", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d841d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#41d862", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#5b41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#9dd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#9d41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d89d", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#414ed8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#417cd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#8941d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#417cd8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d87c", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#414ed8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d8be41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#b1d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d85b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d84162", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41c4d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d8be", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#75d841", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#62d841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#cb41d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d84147", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d84141", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d84741", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d88941", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d84190", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41a3d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d8cb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#aa41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41cbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d86841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d86f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#b141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#41b7d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41bed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#41b1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#41aad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#cb41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#4189d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d89641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d89d41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#4182d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#d8b141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#47d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d841b7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8a341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#415bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d841aa", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d84e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d868", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d8cb41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d84182", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d86f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41d87c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#b7d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d889", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#41d890", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d84168", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d896", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d84162", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#96d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#6841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#6f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#6241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d8b1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d87c", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#c441d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#4190d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d841d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d84189", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#6f41d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#4168d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d87c", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d84e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#aa41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#41b1d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d88941", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#6fd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#62d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#47d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d841b1", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#41d847", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d2d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#c4d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d896", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#4e41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#a3d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#7c41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d8414e", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#4154d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d84175", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d8b741", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d841aa", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#5441d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#9641d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d8415b", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#6841d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4141d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d241d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#bed841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d86241", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d841be", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#416fd8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#41d889", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#d86841", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#4147d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d841aa", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d8419d", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d85b41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d2d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#4ed841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#89d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d8d241", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#9041d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d8c441", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d841c4", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d87c41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#82d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d85441", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#aad841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#6f41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#5bd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#414ed8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#417cd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41d8b7", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#bed841", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d8c441", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8aa41", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#68d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d87c41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d87c41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d88941", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#7c41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d241d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#bed841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d85b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d86241", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#8241d8", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d87c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#41d8aa", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d8cb41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#9041d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d8c441", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d8c441", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d8c441", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d88941", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d8cb", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#a3d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d841d2", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#b141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#47d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d88941", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d88941", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d88941", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#41d8a3", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d86241", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d241d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#bed841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d85b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d86241", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#8241d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d87c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41d8aa", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d88941", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d241d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#41d8c4", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#bed841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d85b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d86241", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#d84190", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#8241d8", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d87c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41d8aa", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d88941", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d87c41", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d88941", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#68d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d87c41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d8cb", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d88941", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#47d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d841aa", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#41d890", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#a3d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#b741d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8aa41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d86241", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d87c41", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#41aad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d88941", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#62d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d8aa41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d841b7", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d841", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d8c441", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d85b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d84190", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#4154d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d8cb41", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#b7d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#bed841", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#a3d841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#96d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#41d8aa", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d88941", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d841aa", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#aad841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#a341d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#41d8a3", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d88241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d841b7", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d88941", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#41d8a3", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#68d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d8cb", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#4162d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#47d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d84162", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#82d841", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#7cd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d8cb", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41d8d2", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d85441", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#9641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d86241", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d86841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#a341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d87c41", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d88241", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41bed8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#b741d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41a3d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d88941", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#62d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d841d2", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d841c4", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#47d841", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d84e", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#41d854", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d8419d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d84190", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d8417c", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#4147d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8d241", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d86f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d84175", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d2d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#cbd841", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#c4d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d889", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41d890", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#5441d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#a3d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d8415b", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#6841d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#5bd841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#54d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d84175", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#414ed8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#417cd8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41d8b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d8d841", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d896", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d8b741", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d841aa", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d8419d", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#62d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#9641d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#8941d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d89641", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d8415b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d87c41", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4141d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d88941", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#b741d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d88941", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41d890", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d841cb", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d87c41", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#62d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d84189", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d87c41", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#9d41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d84190", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d841b7", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#c441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d88941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d88941", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#4196d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#62d841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d89d", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d862", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d841d2", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#7541d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#414ed8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d841b7", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#4175d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#41d8cb", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#d84190", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d841d2", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d87c41", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#47d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d87c", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8416f", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d84190", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#62d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d84190", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d84162", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d87c41", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#47d841", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d8b1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d88941", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d8d241", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d841c4", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d88941", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#5441d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#aad841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d86241", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d841d2", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d8415b", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d84189", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#47d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d8cb", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#4182d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d88941", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#415bd8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41d890", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d87c41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d88941", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d88941", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41a3d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d84190", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d84175", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d86241", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d86841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d87c41", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d88241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d88941", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d89041", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d89d41", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8a341", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d8b741", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d8be41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d8cb41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d8d841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d2d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#cbd841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#c4d841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#b1d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#aad841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#a3d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#90d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#47d841", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d868", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41d87c", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41d882", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d889", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#41d890", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#41d2d8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#41b7d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41bed8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#41b1d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#419dd8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#416fd8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#4162d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#4741d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#5441d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#5b41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#6f41d8", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#a341d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#aa41d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#b141d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#be41d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#b741d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#c441d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d841d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d841d2", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d841cb", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d841be", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d841b7", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d841aa", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d841a3", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d84196", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d8419d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d84190", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d84182", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d84168", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d84162", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d8415b", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d841b7", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#c441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d8d841", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#4168d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d88941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#5bd841", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#4190d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#62d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d8d841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d87c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d88941", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d88941", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d841b1", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#41d847", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#62d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#aa41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#a3d841", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#9dd841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d87c41", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#47d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#41b1d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d87c41", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d86f41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d84175", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#b141d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#cbd841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d8b741", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#68d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#5441d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#6241d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d8415b", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#6841d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d841c4", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#4147d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8d241", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#9041d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d241d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#bed841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d85b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d84190", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d86241", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#8241d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d87c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#41d8aa", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#89d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#416fd8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d841be", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#41d889", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d87c41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#4147d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d8d241", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d84e41", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d87c41", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41a3d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d841d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d841b7", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d8b141", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d8d841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#a3d841", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v6x.json b/docs/public/middleware/graph_px4_fmu-v6x.json index cdc717fa67..559e95c2e7 100644 --- a/docs/public/middleware/graph_px4_fmu-v6x.json +++ b/docs/public/middleware/graph_px4_fmu-v6x.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#4158d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d87241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d8ab41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#b0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#5b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#b041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84164", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#417cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d841b9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#d841c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d858", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41bcd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d841a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#d85d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#69d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#6241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d86b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41d851", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d898", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41d8bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d84179", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41a6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#7041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841ab", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#c5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#b7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#c541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d8416b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d84f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d85641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#5bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8419d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d87941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d87c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#62d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41c3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#4198d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#4191d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8415d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d8414f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d8c141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#41d86e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d891", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8b5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#4151d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#b741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d86441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d88841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#9bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#416ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#9b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d8a441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d8b941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d8c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41b5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84172", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d84156", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#70d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#6941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d84188", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d89d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#6941d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#6941d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#9bd841", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8415d", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8415d", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#7e41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#41c3d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#41d84a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#419fd8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d84a", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41c3d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#419fd8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#b741d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d86441", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d841cf", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d841cf", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#b741d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#7e41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#d841c1", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#4143d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#b741d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#d85d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#9341d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#4191d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d891", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#414ad8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#b041d8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d8ae", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#62d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#b7d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41aed8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d89641", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#4198d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d8b241", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#93d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41d8bc", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#be41d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8419d", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#69d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#a941d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#53d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#5bd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#417cd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d89d41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d843", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#6241d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#7741d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d88a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#9b41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841ab", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d8c841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d87241", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#d88141", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d841a4", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#41d8c3", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#d88841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#9b41d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#a9d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d8414f", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#a2d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d8ab41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#8c41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d8414f", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d8416b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#85d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4175d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d8d1", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d4d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#ccd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d841c8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41d851", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41a6d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d866", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d8a441", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8b5", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#5341d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d858", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#9b41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d85f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#62d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#d84841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41bcd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#85d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#8cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#77d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41b5d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41aed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41a6d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#419fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d85641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#70d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#418ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#4183d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#416ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#4cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d841d6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#d841cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#45d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d841b9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41d84a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#4541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841b2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d8c141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#5b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#6241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d84196", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d84188", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#41d86e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d875", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d84181", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d88a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d84179", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d898", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#b0d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d84156", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#4c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d87241", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841b2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841ab", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#41d883", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d8ab41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84164", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84141", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#7ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d84f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#62d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d88f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d89641", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#cc41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#415fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d841d6", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#4158d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d843", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41d851", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d8cf41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d87c", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8a6", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#5341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#41d89f", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#c5d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d8418f", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#4cd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d86b41", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#a941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84172", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#a241d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d87941", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#bed841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841b2", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#c541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#4166d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#7041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d8414f", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#8541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41d1d8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#4151d8", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d8b941", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d8ca", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#6941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d87941", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#62d841", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#4158d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d87941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#41d8bc", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4175d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#9b41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d8b241", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#4151d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#419fd8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#419fd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#416ed8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d8b941", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d8b941", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d8b941", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d8b941", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d843", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#6241d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#62d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d841cf", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#62d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#62d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#62d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d87941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41d8bc", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4175d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#9b41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d8b241", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#4151d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#4151d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d87941", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41d8bc", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#4175d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#9b41d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d86441", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#62d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d8b241", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d87941", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#6941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#62d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d8b241", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d8ca", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#9b41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#419fd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d87941", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4175d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#be41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d89641", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#4151d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d8b241", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d841b9", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d8b941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#41d851", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d8c841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#6241d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d8d641", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d84179", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#41d8bc", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#41d8ca", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#4c41d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#a2d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41d851", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d841a4", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d8c3", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#417cd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#4166d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#62d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#5bd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d841a4", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#6941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#62d841", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8415d", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#85d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d88a", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41cad8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#9bd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41b5d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#9341d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d85641", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#70d841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d84f41", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41aed8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#69d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d86b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#62d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#5bd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d87941", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#417cd8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#b741d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#416ed8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#be41d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d88f41", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d89d41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#415fd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#45d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d8b241", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#5341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#6241d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d85f", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#7041d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d87c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#c5d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#7e41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d898", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#41d89f", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8b5", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#b7d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#8541d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#bed841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d8ae", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d8414f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#4166d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#c541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#62d841", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41d1d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8a6", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41d851", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41bcd8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#8cd841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#a941d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#9341d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41a6d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d8418f", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#4cd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#a2d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84172", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#7e41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d841a4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#62d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d87941", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d866", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#4198d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41d851", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#6241d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#62d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d87241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d858", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#41d851", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#41d858", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#6241d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#d89d41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#41d883", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#62d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41d851", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#93d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d858", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d843", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41d851", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#4183d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#85d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d858", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d88a", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#416ed8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#62d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41b5d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#62d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#7ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#a941d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#4166d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#41d883", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41d8d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#a2d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#c5d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d88a", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d8c141", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d87941", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#418ad8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#62d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#62d841", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d85f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#62d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d858", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#d85d41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d86b41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d87241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d87941", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d88841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d89d41", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d8a441", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d8ab41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d8b241", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#c5d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#a9d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#8cd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#7ed841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#85d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#62d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#5bd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d858", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#41d86e", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d87c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d88a", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d891", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#41d8ae", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d8c3", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d8d1", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#41cad8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41c3d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41a6d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#419fd8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#4198d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#4191d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#4183d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#417cd8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#415fd8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#4143d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#7741d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#8541d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#8c41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#9341d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#b041d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#d841c1", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841b2", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8419d", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d84188", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d84181", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84172", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d8416b", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8415d", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d84156", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84148", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d87241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41d851", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#6241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#bed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d858", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84164", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41d851", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841ab", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#6241d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#41d883", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41d851", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#93d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d858", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41d851", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d8cf41", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d88141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#6241d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8419d", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41a6d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d89641", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#cc41d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d89d41", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d441d8", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d841d6", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#8c41d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d84196", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#5341d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d841cf", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#4541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#a941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41b5d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#416ed8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#a241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#70d841", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#6941d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d86b41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#c5d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84172", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d87941", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41b5d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#416ed8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#70d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#45d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#8541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#7ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#62d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d87941", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d8ab41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41d851", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#5b41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#6241d8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d85f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#b0d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d8c3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#62d841", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d89a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d84193", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#b641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d847", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#c4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#a141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#415cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#b6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#78d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d89341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#4e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41d863", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#c441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d87841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#41a8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#418cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#4163d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#d841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#4147d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41d8a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#4ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#a841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d885", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#4185d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d8419a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#bdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#a1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#4741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d88c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d841a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d8418c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d8af41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#a8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#5cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d88c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d8a841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d85c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#bd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#d84178", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#cad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#41d878", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#5c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#af41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84171", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#afd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#ca41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d87141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#7841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d841af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d84163", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d86341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#47d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#4178d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#4141d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#63d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#4141d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#7841d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#7841d8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#7841d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#41d8af", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#41d8af", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#4171d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#4171d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#4171d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#41d8d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#41d878", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d86341", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d8a841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#47d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d8d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#5c41d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#47d841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d8d841", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#5c41d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d85541", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d85541", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d85541", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41d8d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#41d878", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d8a841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d84141", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#41d86a", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41d8d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#d8c441", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#41d878", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41afd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d8a841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41afd8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d84141", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#41d86a", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d84141", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#41d86a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#c441d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#41d8d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#71d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#41d878", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d86341", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d8a841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#a1d841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d85541", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#419ad8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d84141", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#4163d8", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41d8b6", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#41d878", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#93d841", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#6ad841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#4ed841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#41d893", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d8416a", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#af41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#c4d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d8d141", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41d863", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d8a841", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d841c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d8a141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#4155d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#414ed8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d8a1", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#a8d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#4147d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#6341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d8d1", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#5cd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41a1d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d85541", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d84141", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#41cad8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d8419a", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#afd841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d1d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d84193", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#41a8d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#d84163", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#afd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#41d1d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#415cd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#41b6d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#d841d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#41bdd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d847", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#8541d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#8cd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#b641d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#d84147", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#7fd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#d841bd", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d841bd", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#41bdd8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#b6d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d841a8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#78d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d87f", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d84e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#8c41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d8418c", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d841a1", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d885", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#7f41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d8417f", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d89a", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#afd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84171", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d87841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8ca", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#41d893", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#47d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#d84741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#418cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#bd41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#55d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d85541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#417fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#41d855", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d841ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d87f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d841d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#4178d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#4171d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d88c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d89341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d89a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#416ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#41d871", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d841af", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d8b641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d8bd41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d885", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d8419a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d8d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#414ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41d8a8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d8a1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d8bd", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#9ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#93d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#4147d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#4741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#85d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d8415c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#7841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41afd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#a141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#8c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#9a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#a841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#4193d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d84193", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#41cad8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#b641d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d8419a", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d89341", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d841b6", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#bd41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d85c41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d8af41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d841a1", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d88c", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#41d893", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#cad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d8a1", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#d84178", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#4741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#4e41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#5541d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#6ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#9341d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8ca", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d84185", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#bdd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d84155", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d87141", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#5cd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#4171d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d8415c", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d84141", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41d8c4", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d85c", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#4185d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d141d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#41bdd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#7141d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d86a41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d88541", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d89341", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d841bd", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d8414e", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d84141", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#ca41d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#4141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d85c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#41d878", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#41d893", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#5541d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#afd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#41d878", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d87f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d8d141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41d85c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d87841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d1d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d8414e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d8a841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d8d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d8d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#9ad841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d84141", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d84141", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d84141", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#414ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d8a1", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d85541", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#a1d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41afd8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#41d893", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#41a8d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#41d893", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#41a8d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#41d893", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#41a8d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#41d878", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#afd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#41d878", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d87f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d8d141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41d85c", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d1d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d8414e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d8a841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#afd841", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#d8c441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#41d878", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d87f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d8d141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#41d893", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#d87841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#d1d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d8414e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#414ed8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#41d893", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#4141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41d85c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#41d878", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#ca41d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#d84741", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#ca41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41d85c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d87841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d8a841", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d8bd41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#41d878", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d841a1", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d87f", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d8d141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#41d893", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d8d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d1d841", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41d8a8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#afd841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#a841d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#4147d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#6ad841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d8414e", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#414ed8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d841a1", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#d841d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#4147d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d84163", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#41d893", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#41a8d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#41d893", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#4141d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#41a8d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#414ed8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d8a1", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#41d8af", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#47d841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#4185d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d85541", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d841d1", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d86341", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d85c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d88541", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#4171d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d8a141", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d8a841", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#41d86a", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d841af", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d8af41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d8b641", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#41d878", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d841a1", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d88c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#41d893", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#cad841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#4155d8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#414ed8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#bdd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d8a1", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41d8b6", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#d84178", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#a1d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#9ad841", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84171", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#93d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#4147d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8ca", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#85d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#6341d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d8d1", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#7841d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d84155", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#63d841", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#6ad841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41a1d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#5cd841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#4163d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d141d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#7141d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#41d893", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8ca", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#4ed841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d841bd", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#bd41d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#418cd8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d8b641", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d885", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d841a1", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#d841d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d87141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d85c", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#5cd841", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d8415c", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d86341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#41d893", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#41a8d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#41d893", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d85c", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#af41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d841a1", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#414ed8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d841a1", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#4147d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d84193", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#41d893", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#414ed8", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#415cd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d841a1", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#41bdd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#a1d841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d847", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#4ed841", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#8cd841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#d84147", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d8a141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#414ed8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d8a141", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d841a1", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#4147d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#d87841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#41d85c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#4ed841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d841a1", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#41d893", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41d863", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#414ed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84e41", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d841a1", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#417fd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d85c", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#8c41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#4e41d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d89a41", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#41d893", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d841af", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#9ad841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#bdd841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#41d878", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41c4d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#a1d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#d841d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#4147d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#5cd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#414ed8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#4147d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d85541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#41d893", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d88c41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#41d893", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#41d893", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8ca", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84171", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d87141", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d86341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d88541", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d89341", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d8a141", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d8ca41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d8d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#cad841", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#c4d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#bdd841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#b6d841", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#a8d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#a1d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#93d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#7fd841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#78d841", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#71d841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#5cd841", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#4ed841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#47d841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d84e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d85c", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#41d871", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#41d878", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d885", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d88c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d8a1", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8ca", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41afd8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41a1d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#419ad8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#4193d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#417fd8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#4178d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#4171d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#414ed8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#4147d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#4741d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#4e41d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#5c41d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#6341d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#7841d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#7f41d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#8c41d8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#9a41d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#b641d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#af41d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#c441d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d141d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d841ca", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d841a8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d841a1", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d84193", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d8418c", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#d84178", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d84163", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#414ed8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d841a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d87841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#41d893", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d87841", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#4147d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#4ed841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#41d893", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41d863", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d8a1", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d885", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d841a1", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d85c41", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#41d893", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#8541d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#4741d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#4147d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d841c4", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d8a141", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#9341d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41afd8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8ca", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#416ad8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#bdd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#4155d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d841af", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#6a41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#9ad841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d87141", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#4178d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41d8c4", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#4141d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#5cd841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#4ed841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d841af", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#9ad841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#7841d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d88541", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#414ed8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#a1d841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84171", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#4147d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d84163", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#4e41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#6ad841", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#b641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#41d893", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_sitl.json b/docs/public/middleware/graph_px4_sitl.json index 4099ac8ea8..2262923a1f 100644 --- a/docs/public/middleware/graph_px4_sitl.json +++ b/docs/public/middleware/graph_px4_sitl.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_fake_magnetometer", "name": "fake_magnetometer", "type": "Module", "color": "#666666"}, {"id": "m_px4_mavlink_debug", "name": "px4_mavlink_debug", "type": "Module", "color": "#666666"}, {"id": "m_work_item_example", "name": "work_item_example", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_pos_control", "name": "fw_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_px4_simple_app", "name": "px4_simple_app", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_fake_imu", "name": "fake_imu", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d86941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#41a2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84169", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#9741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d89241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d84192", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#41d857", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d88b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#97d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8418b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#4157d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#4cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#4c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8418b", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d841c8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#75d841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d84177", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#97d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d87741", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#c6d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41d8b6", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#41d8a9", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#4180d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#7bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#82d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#41cbd8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d8cf41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#4143d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d841d6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d88441", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#4194d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d841c2", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d850", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#41d857", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d8bb41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#6041d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41d89b", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d85c41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d8b441", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#59d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d8a641", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_orbit_status", "color": "#d4d841", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_landing_status", "color": "#d8a041", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_launch_detection_status", "color": "#418ed8", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flight_phase_estimation", "color": "#d84e41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_figure_eight_status", "color": "#41d872", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_landing_gear", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_flaps_setpoint", "color": "#d88b41", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_spoilers_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_tecs_status", "color": "#d84147", "style": "dashed"}, {"source": "m_fw_pos_control", "target": "t_position_controller_status", "color": "#d89941", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d88b41", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#bf41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d8415c", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#9041d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d84192", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d841bb", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d86941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#41d843", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#6ed841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8a2", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d1d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#41d857", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d841c2", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#41d89b", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41b6d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#cd41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#89d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#4180d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d85c41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#4179d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#b241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8a2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#90d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d8d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#82d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#a441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#ab41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41afd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#b941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#59d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d87e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d841cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d841c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d841c2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#4165d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8ad41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#415ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#4157d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d8417e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d84170", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#4541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d8414e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#b9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#41d88e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d894", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#b2d841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#59d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d8bd", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d8b441", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d841b4", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84141", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#60d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#abd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#a4d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#9dd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#a441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#41bdd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#6ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#45d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#4180d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d84a", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d89241", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#416cd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d85e", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#5341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d887", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d8c4", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#89d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#41a9d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#41a2d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#c641d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#9741d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#8241d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#d89941", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#41a9d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#41a2d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#c641d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#9741d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#8241d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#41a9d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#41a2d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#c641d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#9741d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#41d880", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#8241d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#d89941", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#5941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#419bd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d88441", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d8c241", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d86241", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#7b41d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#4165d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#41d8a9", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d85541", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#67d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#4187d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#41d843", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84199", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#4c41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d8414e", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#6e41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#41d894", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d84162", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#cdd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#41d8a9", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#6741d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#67d841", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#41d8cb", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d85541", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#41d8d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#ab41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#d87041", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#4187d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84199", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#4150d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#d8417e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#4c41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d8414e", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#b2d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a0", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d84199", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#419bd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#4187d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d85541", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d894", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#bfd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#8941d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84169", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#53d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84184", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d88b41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#414ad8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d8c841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d865", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d841ad", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#4172d8", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#41d8af", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#416cd8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8d641", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#d84741", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_esc_status", "color": "#4c41d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro_fifo", "color": "#9d41d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro", "color": "#7541d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_accel", "color": "#d841a6", "style": "dashed"}, {"source": "m_fake_magnetometer", "target": "t_sensor_mag", "color": "#4cd841", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_value", "color": "#4157d8", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_key_value", "color": "#b941d8", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_array", "color": "#d87e41", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_vect", "color": "#d8ad41", "style": "dashed"}, {"source": "m_px4_simple_app", "target": "t_vehicle_attitude", "color": "#41d879", "style": "dashed"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d8af", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d879", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d441d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d841c2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d84a", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#b2d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8d641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d879", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#419bd8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d84e41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#418ed8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d841c2", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84184", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41d89b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d841c2", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d84a", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d879", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#41d843", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#8941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d8af", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#a4d841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#90d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#89d841", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d1d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#82d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#6ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#53d841", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#cd41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d88441", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d441d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d841c2", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d850", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d89241", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d841a6", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#4165d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#4150d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#414ad8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d84177", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#4541d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#4c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d879", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#5941d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#bfd841", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d887", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41d89b", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84169", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#41d8d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#7bd841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d88b41", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d8c841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d8cf41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84184", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d841ad", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#416cd8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8a2", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#419bd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d88441", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#41d8cb", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#6ed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d894", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d8af", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#4180d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d1d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d8af", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d84177", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_pos_control", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_pos_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_pos_control", "color": "#41d8af", "style": "normal"}, {"source": "t_wind", "target": "m_fw_pos_control", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_pos_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_pos_control", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_pos_control", "color": "#41d84a", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_pos_control", "color": "#d84177", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_pos_control", "color": "#b241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#7bd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#6ed841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#60d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#b241d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41afd8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#45d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#6e41d8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d84a", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#41d843", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d841a6", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d88441", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#9d41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#7541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#5341d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#41d8a9", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#59d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d88441", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#7bd841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84184", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d84177", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d879", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d8a2", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d841c2", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#6ed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d8af", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#4165d8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#4cd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#4180d8", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#4179d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d86941", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d87041", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d88441", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d89241", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#d89941", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8ad41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d8c241", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#a4d841", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#97d841", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#9dd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#7bd841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#53d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#4cd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#41d843", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#41d857", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d879", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d887", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41d89b", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8a2", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#41cbd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#419bd8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#4187d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#4180d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#4157d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#4150d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#4c41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#5341d8", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#6041d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#6e41d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#8941d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#9041d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#a441d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#b241d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d441d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d841c2", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#d84199", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d84192", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8418b", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84184", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d84177", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d8415c", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84169", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#b241d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d8b441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#6ed841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#6ed841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#60d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#b241d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8a2", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d8af", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#9dd841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#6041d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d441d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d841d6", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d85e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#4180d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d841c2", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#41bdd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#6ed841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d84a", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#d89941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#41d8af", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#89d841", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d84170", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#b2d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d84162", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#4541d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#cdd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#41d879", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#41a2d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#c641d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#41a9d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#9741d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d841c2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#8241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#b241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d84162", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#4541d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#41a9d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#41d879", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#41a2d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#c641d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#9741d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d841c2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#8241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#b241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d84162", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#4541d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#41a9d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#5341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#41d879", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#41a2d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#c641d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#9741d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d841c2", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#8241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d879", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41d865", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#b241d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#8941d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d88441", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#4194d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d8414e", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#4cd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#7bd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#7541d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#4150d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#7b41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#4180d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#d84e41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#41d8af", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#4172d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#d8415c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#41d8af", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#d8a641", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d8c4", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#d85c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#4143d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#b241d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#bf41d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#4172d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d8af", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d8a641", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d8c4", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d85c41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#4143d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d85541", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#67d841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#6741d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#67d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d8af", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#4cd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#7541d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41d865", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#60d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d879", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#53d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#6ed841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#4180d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d841c2", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#4179d8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#415ed8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d84177", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#5341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d88e", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#53d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d841d6", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fake_magnetometer", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_work_item_example", "color": "#4180d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_work_item_example", "color": "#d841a6", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_fake_magnetometer", "name": "fake_magnetometer", "type": "Module", "color": "#666666"}, {"id": "m_px4_mavlink_debug", "name": "px4_mavlink_debug", "type": "Module", "color": "#666666"}, {"id": "m_work_item_example", "name": "work_item_example", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_px4_simple_app", "name": "px4_simple_app", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_fake_imu", "name": "fake_imu", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d886", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#9ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#a5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#a541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#84d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#9e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d88d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d8ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#418dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#41d873", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4173d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#8441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d841d7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41ced8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#4186d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d8d741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#c6d841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4173d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d89a", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#c641d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d86841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#41d866", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#416cd8", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#41bbd8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d841d7", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#41c1d8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#8441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#50d841", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d8a341", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d8d5", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d8415b", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#43d841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d84182", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d84175", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8414e", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d86841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#d87b41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d841ca", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#a5d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d3d841", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d841b6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d84141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#7e41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41b4d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#416cd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#41d873", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d8ae", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d8d741", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#bfd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#6341d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d86841", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#56d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d86141", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#4941d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d341d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#7141d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#d841d1", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#41a1d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#41d8ce", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#41d85f", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#56d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#d89641", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#41d8b4", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#b241d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#41d845", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#415fd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d8416e", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#d84196", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#d85441", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d8ce", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d88d", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#7ed841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#77d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#71d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#d8b041", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d841a3", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#4159d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#41a7d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#9e41d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d8c1", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#7e41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#41d8ae", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#bfd841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#41d873", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#8b41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#41d893", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#7741d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#56d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#b941d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8414e", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#63d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#98d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#91d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d8c8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#84d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#9141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#9e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#77d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#ab41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41ced8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#41c8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#5dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41aed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d86141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#419ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d841b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d841a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d86841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d86e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#4186d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d8419c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d88241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d88941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d84189", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d8417b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d8b641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d84182", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d886", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#4145d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41d89a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#41d8a1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d8ae", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d8d141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#ccd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d8bb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d84154", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#bfd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#b9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#9ed841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#7141d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d86141", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#4941d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#49d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#415fd8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#41d880", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84741", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d841d7", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d841bd", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#41a7d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d84b", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#4179d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d859", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d8417b", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#4145d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#4341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d8ae", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#5041d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84147", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8414e", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#b9d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#5d41d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#d8c441", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#7741d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#d87b41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#b2d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#d8418f", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#6a41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#d89c41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#a541d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d3d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#5641d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#d8418f", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#d89c41", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#a541d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d3d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#5641d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#6a41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#d8418f", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#d89c41", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#a541d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d3d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#5641d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#6a41d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#b2d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#4152d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#98d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841c4", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d85b41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d88941", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#41d5d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d8bd41", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#cc41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#91d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#41d8c8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#9141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#77d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#ab41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#41ced8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#6ad841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#41c1d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d841b0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d87541", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#d87b41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#d88941", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#d88f41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d8a941", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#d84175", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#41d89a", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#41d8a1", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#d8d141", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d84161", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d3d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#abd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#d87b41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#41c1d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#4166d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d3d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d84175", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d87541", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#414bd8", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#d88941", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#ab41d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#41d89a", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#41d8a1", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#9141d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#9841d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#ab41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#41ced8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#6ad841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#41aed8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d841b0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d8419c", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#d88941", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#d88f41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d8a941", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#41d8a1", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#d8d141", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d84161", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#41d8bb", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d84154", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#abd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#98d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d8c8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d8d141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84161", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d8a941", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#d84154", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#41ced8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#6ad841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#abd841", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#41d8a7", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#418dd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d852", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d8ce", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d84e41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#8bd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d84168", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d84175", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#4193d8", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#b9d841", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d86841", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#41d89a", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_esc_status", "color": "#d88f41", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_accel", "color": "#d8d141", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro_fifo", "color": "#d84154", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro", "color": "#41ced8", "style": "dashed"}, {"source": "m_fake_magnetometer", "target": "t_sensor_mag", "color": "#41d8a1", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_key_value", "color": "#5dd841", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_vect", "color": "#4186d8", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_value", "color": "#d84189", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_array", "color": "#d841a9", "style": "dashed"}, {"source": "m_px4_simple_app", "target": "t_vehicle_attitude", "color": "#416cd8", "style": "dashed"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#4193d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#c641d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#416cd8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41aed8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d8ae", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d8414e", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#cc41d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d86841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d8414e", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#41d852", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#98d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#41a7d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8414e", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#b241d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#41d873", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#9141d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d8419c", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#77d841", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#416cd8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#7741d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#8bd841", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#8b41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#84d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d8c8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#ab41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41ced8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#b941d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#63d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#cc41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d841d7", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#41c1d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841c4", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#41a7d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#4193d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d84b", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#418dd8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#4179d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#416cd8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d88941", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d88f41", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d84182", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d8a341", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d84168", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#41d873", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#4152d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d89a", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41d8a1", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41d8a7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d8d141", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#4341d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d8d741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d3d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#bfd841", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d8c1", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#6341d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#41d879", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#41d852", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d8ce", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d84e41", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#9841d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d8d5", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#50d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#4180d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#b9d841", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#414bd8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#4152d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d85b41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841c4", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#9141d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#9e41d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#41d5d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#41a7d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#4193d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#4193d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d8c1", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d8d5", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#49d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#416cd8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8414e", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d8d741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d8414e", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d8416e", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d84196", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#41d8d5", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d8d741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#41d866", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#4193d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d8414e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8414e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#63d841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#a5d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#91d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#41a7d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#77d841", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#ccd841", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#4193d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#5d41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#63d841", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#9ed841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#418dd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d8d141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8414e", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d8bd41", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#d84154", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#41ced8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d841c4", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#41c1d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#41d852", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841c4", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d8d5", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#49d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d8bd41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#bfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#5d41d8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#416cd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#41c1d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#9141d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#9e41d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d8419c", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d88241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8414e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#63d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#cc41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8414e", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#7741d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8414e", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#b941d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d86e41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d88941", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#d8b041", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d8ca41", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d8d741", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#98d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#91d841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#71d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#63d841", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#5dd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#41d852", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d859", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41d85f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#41d873", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d88d", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#41d893", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#41d8a1", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d8ae", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d8c1", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#41d8d5", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#41c1d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#41bbd8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#41a7d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#4193d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#418dd8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#4186d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#4179d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4173d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#415fd8", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#4159d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#4145d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#5d41d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#6341d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#7141d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#7e41d8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#8441d8", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#9841d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#9e41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#ab41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#c641d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d841d7", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d841b6", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d841a3", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d84189", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d84182", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d84161", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d8415b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8414e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#4180d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#4941d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8414e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#63d841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#a5d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d841d7", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#4145d8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d841bd", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d8ae", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#9e41d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d8d741", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#41a7d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d8417b", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#5041d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#bfd841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#4193d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d8b641", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41aed8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#7741d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#d87b41", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#d8418f", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#84d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#416cd8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#bf41d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#d89c41", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#41d8d5", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#d86141", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d3d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#bfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#5d41d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#b2d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#63d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#6a41d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#d8418f", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#84d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#416cd8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#d89c41", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#41d8d5", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#d86141", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d3d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#bfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#5d41d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#bf41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#63d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#6a41d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#416cd8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#84d841", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#d89c41", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#41d8d5", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#d86141", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d3d841", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#bfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#5d41d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#bf41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#63d841", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#6a41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#bfd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#63d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d85b41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41d8a1", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d88941", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d8d141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d8bd41", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41ced8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d841b0", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#418dd8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#6341d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d8414e", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#41c1d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d841ca", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#7ed841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#56d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d3d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#4193d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#d84175", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#d8c441", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#d841a3", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#63d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#41c1d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d841ca", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#7ed841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#56d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d3d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#4193d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d84175", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#d8c441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#63d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#6ad841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d8414e", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#4166d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d87541", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#41d8a1", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d8d141", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#ab41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#bfd841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#b941d8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41c8d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#416cd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#415fd8", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d886", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8414e", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#d84168", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#41aed8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fake_magnetometer", "color": "#416cd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_work_item_example", "color": "#d8d141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_work_item_example", "color": "#d8414e", "style": "normal"}]} \ No newline at end of file From b26dd4d3f3491ce63f2113075e9c63ec808469b1 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Wed, 28 May 2025 09:16:10 +0300 Subject: [PATCH 062/130] Commander: Introduce global_position_relaxed (#24280) To separate accuracy requirements for VTOL hover and cruise. - global_position_relaxed refers to having a valid horizontal velocity aid source in the estimator and a set global reference position, but poses no requirements on the accuracy of the provided position estimate. - Auto flight modes Mission, Loiter and RTL, while in fixed-wing mode, only require the relaxed global position going forward - COM_POS_FS_EPH is thus no longer used on fixed-wing vehicles (resp. VTOL in FW) - rename failsafe_flags.local_position_accuracy_low to failsafe_flags.position_accuracy_low --------- Signed-off-by: RomanBapst Signed-off-by: Silvan Fuhrer Co-authored-by: Silvan --- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 2 - ROMFS/px4fmu_common/init.d/rc.vtol_defaults | 3 - docs/en/config/safety.md | 18 +++- docs/en/msg_docs/FailsafeFlags.md | 2 +- docs/ko/msg_docs/FailsafeFlags.md | 2 +- docs/uk/msg_docs/FailsafeFlags.md | 2 +- docs/zh/msg_docs/FailsafeFlags.md | 2 +- msg/CMakeLists.txt | 2 +- msg/FailsafeFlags.msg | 4 +- msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg | 34 ++++++++ msg/px4_msgs_old/msg/EventV0.msg | 14 ++++ .../translations/all_translations.h | 2 + .../translation_arming_check_reply_v1.h | 84 +++++++++++++++++++ .../translations/translation_event_v1.h | 38 +++++++++ msg/versioned/ArmingCheckReply.msg | 3 +- msg/{ => versioned}/Event.msg | 2 + .../HealthAndArmingChecks.cpp | 8 +- .../checks/estimatorCheck.cpp | 23 ++++- .../checks/estimatorCheck.hpp | 1 + .../checks/externalChecks.cpp | 2 + .../checks/modeCheck.cpp | 15 +++- .../commander/ModeUtil/mode_requirements.cpp | 37 ++++++-- src/modules/commander/commander_params.c | 5 +- src/modules/commander/failsafe/failsafe.cpp | 2 +- src/modules/commander/failsafe/framework.cpp | 1 + 25 files changed, 278 insertions(+), 30 deletions(-) create mode 100644 msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg create mode 100644 msg/px4_msgs_old/msg/EventV0.msg create mode 100644 msg/translation_node/translations/translation_arming_check_reply_v1.h create mode 100644 msg/translation_node/translations/translation_event_v1.h rename msg/{ => versioned}/Event.msg (92%) diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index e6271d8144..9d0db56e7c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -13,8 +13,6 @@ param set-default MAV_TYPE 1 # # Default parameters for fixed wing UAVs. # -# there is a 2.5 factor applied on the _FS thresholds if for invalidation -param set-default COM_POS_FS_EPH 50 param set-default COM_VEL_FS_EVH 3 param set-default COM_POS_LOW_EPH 50 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index b666d59bb8..b4b4b665e6 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -10,9 +10,6 @@ set VEHICLE_TYPE vtol # MAV_TYPE_VTOL_FIXEDROTOR 22 param set-default MAV_TYPE 22 -# there is a 2.5 factor applied on COM_POS_FS_EPH if for invalidation -param set-default COM_POS_FS_EPH 50 - param set-default COM_POS_LOW_EPH 50 param set-default MIS_TAKEOFF_ALT 20 diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index e20991146f..af6c309cd4 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -187,7 +187,23 @@ The following settings also apply, but are not displayed in the QGC UI. ## Position (GNSS) Loss Failsafe -The _Position Loss Failsafe_ is triggered if the quality of the PX4 global position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The _Position Loss Failsafe_ is triggered if the quality of the PX4 position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The sections below cover first the trigger and then the failsafe action taken by the controller. + +### Position Loss Failsafe Trigger + +There are basically two mechanisms in PX4 to trigger position failsafes: +- A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. +- The estimated horizontal position accuracy exceeds a certain threshold. This check is only done on hovering systems (rotary wing vehicles or VTOLs in hover phase). + +The relevant parameters shown below. + +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------- | +| [EKF2_NOAID_TOUT](../advanced_config/parameter_reference.md#EKF2_NOAID_TOUT) | Maximum inertial dead-reckoning time, so the time after the last data sample was received of any sensor that constrains the velocity drift [microseconds]. | +| [COM_POS_FS_EPH](../advanced_config/parameter_reference.md#COM_POS_FS_EPH) | Horizontal position error threshold for hovering vehicles (Multicopters and VTOLs in hover). Fixed-wing vehicles have this value set to infinity.| + +### Position Loss Failsafe Action The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): diff --git a/docs/en/msg_docs/FailsafeFlags.md b/docs/en/msg_docs/FailsafeFlags.md index 164f8bb216..c0763f555c 100644 --- a/docs/en/msg_docs/FailsafeFlags.md +++ b/docs/en/msg_docs/FailsafeFlags.md @@ -58,7 +58,7 @@ bool mission_failure # Mission failure bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) bool wind_limit_exceeded # Wind limit exceeded bool flight_time_limit_exceeded # Maximum flight time exceeded -bool local_position_accuracy_low # Local position estimate has dropped below threshold, but is currently still declared valid +bool position_accuracy_low # Position estimate has dropped below threshold, but is currently still declared valid bool navigator_failure # Navigator failed to execute a mode # Failure detector diff --git a/docs/ko/msg_docs/FailsafeFlags.md b/docs/ko/msg_docs/FailsafeFlags.md index 164f8bb216..c0763f555c 100644 --- a/docs/ko/msg_docs/FailsafeFlags.md +++ b/docs/ko/msg_docs/FailsafeFlags.md @@ -58,7 +58,7 @@ bool mission_failure # Mission failure bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) bool wind_limit_exceeded # Wind limit exceeded bool flight_time_limit_exceeded # Maximum flight time exceeded -bool local_position_accuracy_low # Local position estimate has dropped below threshold, but is currently still declared valid +bool position_accuracy_low # Position estimate has dropped below threshold, but is currently still declared valid bool navigator_failure # Navigator failed to execute a mode # Failure detector diff --git a/docs/uk/msg_docs/FailsafeFlags.md b/docs/uk/msg_docs/FailsafeFlags.md index 844ea20226..5877ada4d4 100644 --- a/docs/uk/msg_docs/FailsafeFlags.md +++ b/docs/uk/msg_docs/FailsafeFlags.md @@ -58,7 +58,7 @@ bool mission_failure # Mission failure bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) bool wind_limit_exceeded # Wind limit exceeded bool flight_time_limit_exceeded # Maximum flight time exceeded -bool local_position_accuracy_low # Local position estimate has dropped below threshold, but is currently still declared valid +bool position_accuracy_low # Position estimate has dropped below threshold, but is currently still declared valid bool navigator_failure # Navigator failed to execute a mode # Failure detector diff --git a/docs/zh/msg_docs/FailsafeFlags.md b/docs/zh/msg_docs/FailsafeFlags.md index 164f8bb216..c0763f555c 100644 --- a/docs/zh/msg_docs/FailsafeFlags.md +++ b/docs/zh/msg_docs/FailsafeFlags.md @@ -58,7 +58,7 @@ bool mission_failure # Mission failure bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) bool wind_limit_exceeded # Wind limit exceeded bool flight_time_limit_exceeded # Maximum flight time exceeded -bool local_position_accuracy_low # Local position estimate has dropped below threshold, but is currently still declared valid +bool position_accuracy_low # Position estimate has dropped below threshold, but is currently still declared valid bool navigator_failure # Navigator failed to execute a mode # Failure detector diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index a0cc5ab1ec..e07888adb3 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -81,7 +81,7 @@ set(msg_files EstimatorStates.msg EstimatorStatus.msg EstimatorStatusFlags.msg - Event.msg + versioned/Event.msg FigureEightStatus.msg FailsafeFlags.msg FailureDetectorStatus.msg diff --git a/msg/FailsafeFlags.msg b/msg/FailsafeFlags.msg index 33240b0759..243a4b5c9e 100644 --- a/msg/FailsafeFlags.msg +++ b/msg/FailsafeFlags.msg @@ -12,6 +12,7 @@ uint32 mode_req_local_alt uint32 mode_req_local_position uint32 mode_req_local_position_relaxed uint32 mode_req_global_position +uint32 mode_req_global_position_relaxed uint32 mode_req_mission uint32 mode_req_offboard_signal uint32 mode_req_home_position @@ -29,6 +30,7 @@ bool local_position_invalid # Local position estimate invalid bool local_position_invalid_relaxed # Local position with reduced accuracy requirements invalid (e.g. flying with optical flow) bool local_velocity_invalid # Local velocity estimate invalid bool global_position_invalid # Global position estimate invalid +bool global_position_invalid_relaxed # Global position estimate invalid with relaxed accuracy requirements bool auto_mission_missing # No mission available bool offboard_control_signal_lost # Offboard signal lost bool home_position_invalid # No home position available @@ -48,7 +50,7 @@ bool mission_failure # Mission failure bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) bool wind_limit_exceeded # Wind limit exceeded bool flight_time_limit_exceeded # Maximum flight time exceeded -bool local_position_accuracy_low # Local position estimate has dropped below threshold, but is currently still declared valid +bool position_accuracy_low # Position estimate has dropped below threshold, but is currently still declared valid bool navigator_failure # Navigator failed to execute a mode # Failure detector diff --git a/msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg b/msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg new file mode 100644 index 0000000000..c417d6a4f0 --- /dev/null +++ b/msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg @@ -0,0 +1,34 @@ +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +uint8 request_id +uint8 registration_id + +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 + +uint8 health_component_index # HEALTH_COMPONENT_INDEX_* +bool health_component_is_present +bool health_component_warning +bool health_component_error + +bool can_arm_and_run # whether arming is possible, and if it's a navigation mode, if it can run + +uint8 num_events + +EventV0[5] events + +# Mode requirements +bool mode_req_angular_velocity +bool mode_req_attitude +bool mode_req_local_alt +bool mode_req_local_position +bool mode_req_local_position_relaxed +bool mode_req_global_position +bool mode_req_mission +bool mode_req_home_position +bool mode_req_prevent_arming +bool mode_req_manual_control + + +uint8 ORB_QUEUE_LENGTH = 4 diff --git a/msg/px4_msgs_old/msg/EventV0.msg b/msg/px4_msgs_old/msg/EventV0.msg new file mode 100644 index 0000000000..84351a36aa --- /dev/null +++ b/msg/px4_msgs_old/msg/EventV0.msg @@ -0,0 +1,14 @@ +# this message is required here in the msg_old folder because other msg are depending on it +# Events interface + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +uint32 id # Event ID +uint16 event_sequence # Event sequence number +uint8[25] arguments # (optional) arguments, depend on event id + +uint8 log_levels # Log levels: 4 bits MSB: internal, 4 bits LSB: external + +uint8 ORB_QUEUE_LENGTH = 16 diff --git a/msg/translation_node/translations/all_translations.h b/msg/translation_node/translations/all_translations.h index 21b128c03c..22202033f1 100644 --- a/msg/translation_node/translations/all_translations.h +++ b/msg/translation_node/translations/all_translations.h @@ -13,3 +13,5 @@ #include "translation_vehicle_status_v1.h" #include "translation_airspeed_validated_v1.h" #include "translation_vehicle_attitude_setpoint_v1.h" +#include "translation_arming_check_reply_v1.h" +#include "translation_event_v1.h" diff --git a/msg/translation_node/translations/translation_arming_check_reply_v1.h b/msg/translation_node/translations/translation_arming_check_reply_v1.h new file mode 100644 index 0000000000..7753ce96c2 --- /dev/null +++ b/msg/translation_node/translations/translation_arming_check_reply_v1.h @@ -0,0 +1,84 @@ +/**************************************************************************** + * Copyright (c) 2025 PX4 Development Team. + * SPDX-License-Identifier: BSD-3-Clause + ****************************************************************************/ +#pragma once + +// Translate ArmingCheckReply v0 <--> v1 +#include +#include +#include "translation_event_v1.h" + +class ArmingCheckReplyV1Translation { +public: + using MessageOlder = px4_msgs_old::msg::ArmingCheckReplyV0; + static_assert(MessageOlder::MESSAGE_VERSION == 0); + + using MessageNewer = px4_msgs::msg::ArmingCheckReply; + static_assert(MessageNewer::MESSAGE_VERSION == 1); + + static constexpr const char* kTopic = "/fmu/in/arming_check_reply"; + + static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { + msg_newer.timestamp = msg_older.timestamp; + + msg_newer.request_id = msg_older.request_id; + msg_newer.registration_id = msg_older.registration_id; + + msg_newer.health_component_index = msg_older.health_component_index; + msg_newer.health_component_is_present = msg_older.health_component_is_present; + msg_newer.health_component_warning = msg_older.health_component_warning; + msg_newer.health_component_error = msg_older.health_component_error; + + msg_newer.can_arm_and_run = msg_older.can_arm_and_run; + + + for (std::size_t i = 0; i < msg_newer.events.size();i++) { + EventV1Translation::fromOlder(msg_older.events.at(i), msg_newer.events.at(i)); + } + + + msg_newer.mode_req_angular_velocity = msg_older.mode_req_angular_velocity; + msg_newer.mode_req_attitude = msg_older.mode_req_attitude; + msg_newer.mode_req_local_alt = msg_older.mode_req_local_alt; + msg_newer.mode_req_local_position = msg_older.mode_req_local_position; + msg_newer.mode_req_local_position_relaxed = msg_older.mode_req_local_position_relaxed; + msg_newer.mode_req_global_position = msg_older.mode_req_global_position; + msg_newer.mode_req_global_position_relaxed = false; + msg_newer.mode_req_mission = msg_older.mode_req_mission; + msg_newer.mode_req_home_position = msg_older.mode_req_home_position; + msg_newer.mode_req_prevent_arming = msg_older.mode_req_prevent_arming; + msg_newer.mode_req_manual_control = msg_older.mode_req_manual_control; + + } + + static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { + msg_older.timestamp = msg_newer.timestamp; + + msg_older.request_id = msg_newer.request_id; + msg_older.registration_id = msg_newer.registration_id; + + msg_older.health_component_index = msg_newer.health_component_index; + msg_older.health_component_is_present = msg_newer.health_component_is_present; + msg_older.health_component_warning = msg_newer.health_component_warning; + msg_older.health_component_error = msg_newer.health_component_error; + + msg_older.can_arm_and_run = msg_newer.can_arm_and_run; + + for (std::size_t i = 0; i < msg_older.events.size();i++) { + EventV1Translation::toOlder(msg_newer.events.at(i), msg_older.events.at(i)); + } + + msg_older.mode_req_angular_velocity = msg_newer.mode_req_angular_velocity; + msg_older.mode_req_attitude = msg_newer.mode_req_attitude; + msg_older.mode_req_local_alt = msg_newer.mode_req_local_alt; + msg_older.mode_req_local_position = msg_newer.mode_req_local_position; + msg_older.mode_req_global_position = msg_newer.mode_req_global_position; + msg_older.mode_req_mission = msg_newer.mode_req_mission; + msg_older.mode_req_home_position = msg_newer.mode_req_home_position; + msg_older.mode_req_prevent_arming = msg_newer.mode_req_prevent_arming; + msg_older.mode_req_manual_control = msg_newer.mode_req_manual_control; + } +}; + +REGISTER_TOPIC_TRANSLATION_DIRECT(ArmingCheckReplyV1Translation); diff --git a/msg/translation_node/translations/translation_event_v1.h b/msg/translation_node/translations/translation_event_v1.h new file mode 100644 index 0000000000..edf2a74a9d --- /dev/null +++ b/msg/translation_node/translations/translation_event_v1.h @@ -0,0 +1,38 @@ +/**************************************************************************** + * Copyright (c) 2025 PX4 Development Team. + * SPDX-License-Identifier: BSD-3-Clause + ****************************************************************************/ +#pragma once + +// Translate Event v0 <--> v1 +#include +#include + +class EventV1Translation { +public: + using MessageOlder = px4_msgs_old::msg::EventV0; + static_assert(MessageOlder::MESSAGE_VERSION == 0); + + using MessageNewer = px4_msgs::msg::Event; + static_assert(MessageNewer::MESSAGE_VERSION == 1); + + static constexpr const char* kTopic = "fmu/out/event"; + + static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { + msg_newer.timestamp = msg_older.timestamp; + msg_newer.id = msg_older.id; + msg_newer.event_sequence = msg_older.event_sequence; + msg_newer.arguments = msg_older.arguments; + msg_newer.log_levels = msg_older.log_levels; + } + + static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { + msg_older.timestamp = msg_newer.timestamp; + msg_older.id = msg_newer.id; + msg_older.event_sequence = msg_newer.event_sequence; + msg_older.arguments = msg_newer.arguments; + msg_older.log_levels = msg_newer.log_levels; + } +}; + +REGISTER_TOPIC_TRANSLATION_DIRECT(EventV1Translation); diff --git a/msg/versioned/ArmingCheckReply.msg b/msg/versioned/ArmingCheckReply.msg index 4c1616d849..0efcc21738 100644 --- a/msg/versioned/ArmingCheckReply.msg +++ b/msg/versioned/ArmingCheckReply.msg @@ -1,4 +1,4 @@ -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # time since system start (microseconds) @@ -25,6 +25,7 @@ bool mode_req_local_alt bool mode_req_local_position bool mode_req_local_position_relaxed bool mode_req_global_position +bool mode_req_global_position_relaxed bool mode_req_mission bool mode_req_home_position bool mode_req_prevent_arming diff --git a/msg/Event.msg b/msg/versioned/Event.msg similarity index 92% rename from msg/Event.msg rename to msg/versioned/Event.msg index df1dd4a97d..ed8d841ebd 100644 --- a/msg/Event.msg +++ b/msg/versioned/Event.msg @@ -1,4 +1,6 @@ # Events interface +uint32 MESSAGE_VERSION = 1 + uint64 timestamp # time since system start (microseconds) uint32 id # Event ID diff --git a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp index f4f91d0450..ffb72e6d78 100644 --- a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp +++ b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.cpp @@ -45,6 +45,7 @@ HealthAndArmingChecks::HealthAndArmingChecks(ModuleParams *parent, vehicle_statu _failsafe_flags.local_position_invalid_relaxed = true; _failsafe_flags.local_velocity_invalid = true; _failsafe_flags.global_position_invalid = true; + _failsafe_flags.global_position_invalid_relaxed = true; _failsafe_flags.auto_mission_missing = true; _failsafe_flags.offboard_control_signal_lost = true; _failsafe_flags.home_position_invalid = true; @@ -54,7 +55,10 @@ bool HealthAndArmingChecks::update(bool force_reporting, bool is_arming_request) { _reporter.reset(); - _reporter.prepare(_context.status().vehicle_type); + // treat VTOLs in transition mode as fixed-wing - this is not in line with what's published as vehicle_status_s::vehicle_type + const uint8_t vehicle_type = _context.status().in_transition_mode ? vehicle_status_s::VEHICLE_TYPE_FIXED_WING : + _context.status().vehicle_type; + _reporter.prepare(vehicle_type); _context.setIsArmingRequest(is_arming_request); @@ -78,7 +82,7 @@ bool HealthAndArmingChecks::update(bool force_reporting, bool is_arming_request) _reporter._mavlink_log_pub = &_mavlink_log_pub; _reporter.reset(); - _reporter.prepare(_context.status().vehicle_type); + _reporter.prepare(vehicle_type); for (unsigned i = 0; i < sizeof(_checks) / sizeof(_checks[0]); ++i) { if (!_checks[i]) { diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 8d1dbbd2df..fa7def7727 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -633,10 +633,18 @@ void EstimatorChecks::checkGps(const Context &context, Report &reporter, const s void EstimatorChecks::lowPositionAccuracy(const Context &context, Report &reporter, const vehicle_local_position_s &lpos) const { - const bool local_position_valid_but_low_accuracy = !reporter.failsafeFlags().local_position_invalid - && (_param_com_low_eph.get() > FLT_EPSILON && lpos.eph > _param_com_low_eph.get()); - if (!reporter.failsafeFlags().local_position_accuracy_low && local_position_valid_but_low_accuracy + bool position_valid_but_low_accuracy = false; + + if ((reporter.failsafeFlags().mode_req_global_position && !reporter.failsafeFlags().global_position_invalid) || + (reporter.failsafeFlags().mode_req_global_position_relaxed + && !reporter.failsafeFlags().global_position_invalid_relaxed) || + (reporter.failsafeFlags().mode_req_local_position && !reporter.failsafeFlags().local_position_invalid)) { + + position_valid_but_low_accuracy = (_param_com_low_eph.get() > FLT_EPSILON && lpos.eph > _param_com_low_eph.get()); + } + + if (!reporter.failsafeFlags().position_accuracy_low && position_valid_but_low_accuracy && _param_com_pos_low_act.get()) { // only report if armed @@ -658,7 +666,7 @@ void EstimatorChecks::lowPositionAccuracy(const Context &context, Report &report } } - reporter.failsafeFlags().local_position_accuracy_low = local_position_valid_but_low_accuracy; + reporter.failsafeFlags().position_accuracy_low = position_valid_but_low_accuracy; } void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_flt_fail_innov_heading, @@ -698,6 +706,12 @@ void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_f !checkPosVelValidity(now, global_pos_valid, gpos.eph, lpos_eph_threshold, gpos.timestamp, _last_gpos_fail_time_us, !failsafe_flags.global_position_invalid); + // for relaxed global condition we don't have any accuracy requirement + const float pos_eph_relaxed_treshold = INFINITY; + failsafe_flags.global_position_invalid_relaxed = !checkPosVelValidity(now, global_pos_valid, gpos.eph, + pos_eph_relaxed_treshold, gpos.timestamp, _last_gpos_relaxed_fail_time_us, + !failsafe_flags.global_position_invalid_relaxed); + // Additional warning if the system is about to enter position-loss failsafe after dead-reckoning period const float eph_critical = 2.5f * lpos_eph_threshold; // threshold used to trigger the navigation failsafe const float gpos_critical_warning_thrld = math::max(0.9f * eph_critical, math::max(eph_critical - 10.f, 0.f)); @@ -712,6 +726,7 @@ void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_f || estimator_status_flags.cs_wind_dead_reckoning; if (!failsafe_flags.global_position_invalid + && failsafe_flags.mode_req_global_position && !_nav_failure_imminent_warned && gpos.eph > gpos_critical_warning_thrld && dead_reckoning) { diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp index 0e10484023..13b351c986 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp @@ -96,6 +96,7 @@ private: uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; hrt_abstime _last_gpos_fail_time_us{0}; ///< Last time that the global position validity recovery check failed (usec) + hrt_abstime _last_gpos_relaxed_fail_time_us{0}; ///< Last time that the global position relaxed validity recovery check failed (usec) hrt_abstime _last_lpos_fail_time_us{0}; ///< Last time that the local position validity recovery check failed (usec) hrt_abstime _last_lpos_relaxed_fail_time_us{0}; ///< Last time that the relaxed local position validity recovery check failed (usec) hrt_abstime _last_lvel_fail_time_us{0}; ///< Last time that the local velocity validity recovery check failed (usec) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp b/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp index 8ef3c5cfa9..b1f2abc064 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp @@ -173,6 +173,8 @@ void ExternalChecks::checkAndReport(const Context &context, Report &reporter) reporter.failsafeFlags().mode_req_local_position_relaxed); setOrClearRequirementBits(reply.mode_req_global_position, nav_mode_id, replaces_nav_state, reporter.failsafeFlags().mode_req_global_position); + setOrClearRequirementBits(reply.mode_req_global_position_relaxed, nav_mode_id, replaces_nav_state, + reporter.failsafeFlags().mode_req_global_position_relaxed); setOrClearRequirementBits(reply.mode_req_mission, nav_mode_id, replaces_nav_state, reporter.failsafeFlags().mode_req_mission); setOrClearRequirementBits(reply.mode_req_home_position, nav_mode_id, replaces_nav_state, diff --git a/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp index 7352a6bbfe..d13a4a19ae 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/modeCheck.cpp @@ -86,16 +86,27 @@ void ModeChecks::checkAndReport(const Context &context, Report &reporter) reporter.clearCanRunBits(local_position_modes); } + NavModes global_position_modes = NavModes::None; + if (reporter.failsafeFlags().global_position_invalid && reporter.failsafeFlags().mode_req_global_position != 0) { + global_position_modes = (NavModes)reporter.failsafeFlags().mode_req_global_position; + } + + if (reporter.failsafeFlags().global_position_invalid_relaxed + && reporter.failsafeFlags().mode_req_global_position_relaxed != 0) { + global_position_modes = global_position_modes | (NavModes)reporter.failsafeFlags().mode_req_global_position_relaxed; + } + + if (global_position_modes != NavModes::None) { /* EVENT * @description * The available positioning data is not sufficient to execute the selected mode. */ - reporter.armingCheckFailure((NavModes)reporter.failsafeFlags().mode_req_global_position, + reporter.armingCheckFailure(global_position_modes, health_component_t::global_position_estimate, events::ID("check_modes_global_pos"), events::Log::Error, "Navigation error: No valid global position estimate"); - reporter.clearCanRunBits((NavModes)reporter.failsafeFlags().mode_req_global_position); + reporter.clearCanRunBits(global_position_modes); } if (reporter.failsafeFlags().local_altitude_invalid && reporter.failsafeFlags().mode_req_local_alt != 0) { diff --git a/src/modules/commander/ModeUtil/mode_requirements.cpp b/src/modules/commander/ModeUtil/mode_requirements.cpp index 555b564d97..5c6fa30295 100644 --- a/src/modules/commander/ModeUtil/mode_requirements.cpp +++ b/src/modules/commander/ModeUtil/mode_requirements.cpp @@ -50,6 +50,7 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags) flags.mode_req_local_position = 0; flags.mode_req_local_position_relaxed = 0; flags.mode_req_global_position = 0; + flags.mode_req_global_position_relaxed = 0; flags.mode_req_local_alt = 0; flags.mode_req_mission = 0; flags.mode_req_offboard_signal = 0; @@ -85,8 +86,16 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags) // NAVIGATION_STATE_AUTO_MISSION setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_angular_velocity); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_attitude); - setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_local_position); - setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_global_position); + + if (vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_global_position_relaxed); + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_local_position_relaxed); + + } else { + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_global_position); + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_local_position); + } + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_local_alt); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_mission); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION, flags.mode_req_wind_and_flight_time_compliance); @@ -94,16 +103,32 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags) // NAVIGATION_STATE_AUTO_LOITER setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_angular_velocity); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_attitude); - setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_local_position); - setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_global_position); + + if (vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_global_position_relaxed); + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_local_position_relaxed); + + } else { + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_global_position); + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_local_position); + } + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_local_alt); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_wind_and_flight_time_compliance); // NAVIGATION_STATE_AUTO_RTL setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_angular_velocity); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_attitude); - setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_local_position); - setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_global_position); + + if (vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_global_position_relaxed); + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_local_position_relaxed); + + } else { + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_global_position); + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_local_position); + } + setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_local_alt); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_home_position); setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_prevent_arming); diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 3f350618b6..c1b77b6721 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -513,12 +513,13 @@ PARAM_DEFINE_INT32(COM_ARM_AUTH_MET, 0); PARAM_DEFINE_FLOAT(COM_ARM_AUTH_TO, 1); /** - * Horizontal position error threshold. + * Horizontal position error threshold for hovering systems * * This is the horizontal position error (EPH) threshold that will trigger a failsafe. - * The default is appropriate for a multicopter. Can be increased for a fixed-wing. * If the previous position error was below this threshold, there is an additional * factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). + * Only used for multicopters and VTOLs in hover mode. + * Independent from estimator positioning data timeout threshold (see EKF2_NOAID_TOUT). * * Set to -1 to disable. * diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index 6d2bc83d83..905d24491c 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -532,7 +532,7 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state, // trigger Low Position Accuracy Failsafe (only in auto mission and auto loiter) if (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION || state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER) { - CHECK_FAILSAFE(status_flags, local_position_accuracy_low, fromPosLowActParam(_param_com_pos_low_act.get())); + CHECK_FAILSAFE(status_flags, position_accuracy_low, fromPosLowActParam(_param_com_pos_low_act.get())); } if (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF || diff --git a/src/modules/commander/failsafe/framework.cpp b/src/modules/commander/failsafe/framework.cpp index 3de8305702..0632c0681e 100644 --- a/src/modules/commander/failsafe/framework.cpp +++ b/src/modules/commander/failsafe/framework.cpp @@ -697,6 +697,7 @@ bool FailsafeBase::modeCanRun(const failsafe_flags_s &status_flags, uint8_t mode (!status_flags.local_position_invalid || ((status_flags.mode_req_local_position & mode_mask) == 0)) && (!status_flags.local_position_invalid_relaxed || ((status_flags.mode_req_local_position_relaxed & mode_mask) == 0)) && (!status_flags.global_position_invalid || ((status_flags.mode_req_global_position & mode_mask) == 0)) && + (!status_flags.global_position_invalid_relaxed || ((status_flags.mode_req_global_position_relaxed & mode_mask) == 0)) && (!status_flags.local_altitude_invalid || ((status_flags.mode_req_local_alt & mode_mask) == 0)) && (!status_flags.auto_mission_missing || ((status_flags.mode_req_mission & mode_mask) == 0)) && (!status_flags.offboard_control_signal_lost || ((status_flags.mode_req_offboard_signal & mode_mask) == 0)) && From ac80958cc5d882439cc596cc3015d7c657a23f15 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 6 May 2025 09:35:42 +0200 Subject: [PATCH 063/130] differential: seperate actuator control --- src/modules/rover_differential/CMakeLists.txt | 2 + .../DifferentialActControl/CMakeLists.txt | 38 ++++++ .../DifferentialActControl.cpp | 125 ++++++++++++++++++ .../DifferentialActControl.hpp | 121 +++++++++++++++++ .../rover_differential/RoverDifferential.cpp | 74 +---------- .../rover_differential/RoverDifferential.hpp | 57 +------- 6 files changed, 292 insertions(+), 125 deletions(-) create mode 100644 src/modules/rover_differential/DifferentialActControl/CMakeLists.txt create mode 100644 src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp create mode 100644 src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp diff --git a/src/modules/rover_differential/CMakeLists.txt b/src/modules/rover_differential/CMakeLists.txt index a850e5949c..ebae1e8723 100644 --- a/src/modules/rover_differential/CMakeLists.txt +++ b/src/modules/rover_differential/CMakeLists.txt @@ -31,6 +31,7 @@ # ############################################################################ +add_subdirectory(DifferentialActControl) add_subdirectory(DifferentialRateControl) add_subdirectory(DifferentialAttControl) add_subdirectory(DifferentialVelControl) @@ -43,6 +44,7 @@ px4_add_module( RoverDifferential.cpp RoverDifferential.hpp DEPENDS + DifferentialActControl DifferentialRateControl DifferentialAttControl DifferentialVelControl diff --git a/src/modules/rover_differential/DifferentialActControl/CMakeLists.txt b/src/modules/rover_differential/DifferentialActControl/CMakeLists.txt new file mode 100644 index 0000000000..b3ab8187bd --- /dev/null +++ b/src/modules/rover_differential/DifferentialActControl/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(DifferentialActControl + DifferentialActControl.cpp +) + +target_include_directories(DifferentialActControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp new file mode 100644 index 0000000000..dd9c8c99e0 --- /dev/null +++ b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp @@ -0,0 +1,125 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "DifferentialActControl.hpp" + +using namespace time_literals; + +DifferentialActControl::DifferentialActControl(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); +} + +void DifferentialActControl::updateParams() +{ + ModuleParams::updateParams(); + + if (_param_ro_accel_limit.get() > FLT_EPSILON && _param_ro_max_thr_speed.get() > FLT_EPSILON) { + _adjusted_throttle_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get()); + } +} + +void DifferentialActControl::updateActControl() +{ + const hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + + // Motor control + if (_rover_throttle_setpoint_sub.updated()) { + rover_throttle_setpoint_s rover_throttle_setpoint{}; + _rover_throttle_setpoint_sub.copy(&rover_throttle_setpoint); + _throttle_setpoint = rover_throttle_setpoint.throttle_body_x; + } + + if (_rover_steering_setpoint_sub.updated()) { + rover_steering_setpoint_s rover_steering_setpoint{}; + _rover_steering_setpoint_sub.copy(&rover_steering_setpoint); + _speed_diff_setpoint = rover_steering_setpoint.normalized_speed_diff; + } + + if (PX4_ISFINITE(_throttle_setpoint) && PX4_ISFINITE(_speed_diff_setpoint)) { + actuator_motors_s actuator_motors_sub{}; + _actuator_motors_sub.copy(&actuator_motors_sub); + const float current_throttle = (actuator_motors_sub.control[0] + actuator_motors_sub.control[1]) / 2.f; + const float adjusted_throttle_setpoint = RoverControl::throttleControl(_adjusted_throttle_setpoint, + _throttle_setpoint, current_throttle, _param_ro_accel_limit.get(), + _param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), dt); + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + computeInverseKinematics(adjusted_throttle_setpoint, _speed_diff_setpoint).copyTo(actuator_motors.control); + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + + } + +} + +Vector2f DifferentialActControl::computeInverseKinematics(float throttle, const float speed_diff_normalized) +{ + float max_motor_command = fabsf(throttle) + fabsf(speed_diff_normalized); + + if (max_motor_command > 1.0f) { // Prioritize yaw rate if a normalized motor command exceeds limit of 1 + float excess = fabsf(max_motor_command - 1.0f); + throttle -= sign(throttle) * excess; + } + + // Calculate the left and right wheel speeds + return Vector2f(throttle - speed_diff_normalized, + throttle + speed_diff_normalized); +} + +void DifferentialActControl::manualManualMode() +{ + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = hrt_absolute_time(); + rover_steering_setpoint.normalized_speed_diff = manual_control_setpoint.roll; + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); +} + +void DifferentialActControl::stopVehicle() +{ + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + actuator_motors.control[0] = 0.f; + actuator_motors.control[1] = 0.f; + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); +} diff --git a/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp new file mode 100644 index 0000000000..ff893fbfbb --- /dev/null +++ b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp @@ -0,0 +1,121 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include + +/** + * @brief Class for differential actuator control. + */ +class DifferentialActControl : public ModuleParams +{ +public: + /** + * @brief Constructor for DifferentialActControl. + * @param parent The parent ModuleParams object. + */ + DifferentialActControl(ModuleParams *parent); + ~DifferentialActControl() = default; + + /** + * @brief Generate and publish actuatorMotors setpoints from roverThrottleSetpoint/roverSteeringSetpoint. + */ + void updateActControl(); + + /** + * @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint. + */ + void manualManualMode(); + + /** + * @brief Stop the vehicle by sending 0 commands to motors and servos. + */ + void stopVehicle(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + /** + * @brief Compute normalized motor commands based on normalized setpoints. + * @param throttle Normalized speed in body x direction [-1, 1]. + * @param speed_diff_normalized Speed difference between left and right wheels [-1, 1]. + * @return Motor speeds for the right and left motors [-1, 1]. + */ + Vector2f computeInverseKinematics(float throttle, float speed_diff_normalized); + + // uORB subscriptions + uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; + uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)}; + uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)}; + uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; + + // uORB publications + uORB::Publication _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; + uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; + + // Variables + hrt_abstime _timestamp{0}; + float _throttle_setpoint{NAN}; + float _speed_diff_setpoint{NAN}; + + // Controllers + SlewRate _adjusted_throttle_setpoint{0.f}; + + // Parameters + DEFINE_PARAMETERS( + (ParamInt) _param_r_rev, + (ParamFloat) _param_ro_accel_limit, + (ParamFloat) _param_ro_decel_limit, + (ParamFloat) _param_ro_max_thr_speed + ) +}; diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index 9a2a71646a..99dd28d55f 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -39,8 +39,6 @@ RoverDifferential::RoverDifferential() : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) { - _rover_throttle_setpoint_pub.advertise(); - _rover_steering_setpoint_pub.advertise(); updateParams(); } @@ -53,10 +51,6 @@ bool RoverDifferential::init() void RoverDifferential::updateParams() { ModuleParams::updateParams(); - - if (_param_ro_accel_limit.get() > FLT_EPSILON && _param_ro_max_thr_speed.get() > FLT_EPSILON) { - _throttle_body_x_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get()); - } } void RoverDifferential::Run() @@ -65,10 +59,6 @@ void RoverDifferential::Run() updateParams(); } - const hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - _differential_pos_control.updatePosControl(); _differential_vel_control.updateVelControl(); _differential_att_control.updateAttControl(); @@ -83,74 +73,18 @@ void RoverDifferential::Run() && !_vehicle_control_mode.flag_control_rates_enabled; if (full_manual_mode_enabled) { // Manual mode - generateSteeringAndThrottleSetpoint(); + _differential_act_control.manualManualMode(); } if (_vehicle_control_mode.flag_armed) { - generateActuatorSetpoint(); + _differential_act_control.updateActControl(); + } else { + _differential_act_control.stopVehicle(); } } -void RoverDifferential::generateSteeringAndThrottleSetpoint() -{ - manual_control_setpoint_s manual_control_setpoint{}; - - if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = _timestamp; - rover_steering_setpoint.normalized_speed_diff = manual_control_setpoint.roll; - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - } -} - -void RoverDifferential::generateActuatorSetpoint() -{ - if (_rover_throttle_setpoint_sub.updated()) { - _rover_throttle_setpoint_sub.copy(&_rover_throttle_setpoint); - } - - if (_actuator_motors_sub.updated()) { - actuator_motors_s actuator_motors{}; - _actuator_motors_sub.copy(&actuator_motors); - _current_throttle_body_x = (actuator_motors.control[0] + actuator_motors.control[1]) / 2.f; - } - - if (_rover_steering_setpoint_sub.updated()) { - _rover_steering_setpoint_sub.copy(&_rover_steering_setpoint); - } - - const float throttle_body_x = RoverControl::throttleControl(_throttle_body_x_setpoint, - _rover_throttle_setpoint.throttle_body_x, _current_throttle_body_x, _param_ro_accel_limit.get(), - _param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), _dt); - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); - computeInverseKinematics(throttle_body_x, - _rover_steering_setpoint.normalized_speed_diff).copyTo(actuator_motors.control); - actuator_motors.timestamp = _timestamp; - _actuator_motors_pub.publish(actuator_motors); -} - -Vector2f RoverDifferential::computeInverseKinematics(float throttle_body_x, const float speed_diff_normalized) -{ - float max_motor_command = fabsf(throttle_body_x) + fabsf(speed_diff_normalized); - - if (max_motor_command > 1.0f) { // Prioritize yaw rate if a normalized motor command exceeds limit of 1 - float excess = fabsf(max_motor_command - 1.0f); - throttle_body_x -= sign(throttle_body_x) * excess; - } - - // Calculate the left and right wheel speeds - return Vector2f(throttle_body_x - speed_diff_normalized, - throttle_body_x + speed_diff_normalized); -} - int RoverDifferential::task_spawn(int argc, char *argv[]) { RoverDifferential *instance = new RoverDifferential(); diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index 5a98ef7d3c..73fb3e735d 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -40,22 +40,13 @@ #include #include -// Libraries -#include -#include - // uORB includes #include -#include -#include #include -#include -#include -#include #include -#include // Local includes +#include "DifferentialActControl/DifferentialActControl.hpp" #include "DifferentialRateControl/DifferentialRateControl.hpp" #include "DifferentialAttControl/DifferentialAttControl.hpp" #include "DifferentialVelControl/DifferentialVelControl.hpp" @@ -91,59 +82,15 @@ protected: private: void Run() override; - /** - * @brief Generate and publish roverSteeringSetpoint and roverThrottleSetpoint from manualControlSetpoint (Manual Mode). - */ - void generateSteeringAndThrottleSetpoint(); - - /** - * @brief Generate and publish actuatorMotors setpoints from roverThrottleSetpoint/roverSteeringSetpoint. - */ - void generateActuatorSetpoint(); - - /** - * @brief Compute normalized motor commands based on normalized setpoints. - * @param throttle_body_x Normalized speed in body x direction [-1, 1]. - * @param speed_diff_normalized Speed difference between left and right wheels [-1, 1]. - * @return Motor speeds for the right and left motors [-1, 1]. - */ - Vector2f computeInverseKinematics(float throttle_body_x, float speed_diff_normalized); - // uORB subscriptions uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; - uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)}; - uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; - uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; vehicle_control_mode_s _vehicle_control_mode{}; - rover_steering_setpoint_s _rover_steering_setpoint{}; - rover_throttle_setpoint_s _rover_throttle_setpoint{}; - - // uORB publications - uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; - uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; // Class instances + DifferentialActControl _differential_act_control{this}; DifferentialRateControl _differential_rate_control{this}; DifferentialAttControl _differential_att_control{this}; DifferentialVelControl _differential_vel_control{this}; DifferentialPosControl _differential_pos_control{this}; - - // Variables - hrt_abstime _timestamp{0}; - float _dt{0.f}; - float _current_throttle_body_x{0.f}; - - // Controllers - SlewRate _throttle_body_x_setpoint{0.f}; - - // Parameters - DEFINE_PARAMETERS( - (ParamInt) _param_r_rev, - (ParamFloat) _param_ro_accel_limit, - (ParamFloat) _param_ro_decel_limit, - (ParamFloat) _param_ro_max_thr_speed - ) }; From d5dc0a7eb86e63a0318464ffb3cc8470c6a75ecd Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 6 May 2025 11:06:22 +0200 Subject: [PATCH 064/130] differential: update position control --- .../DifferentialPosControl.cpp | 236 ++++++++---------- .../DifferentialPosControl.hpp | 28 +-- 2 files changed, 111 insertions(+), 153 deletions(-) diff --git a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp index f2f37d0a0a..06363c42cb 100644 --- a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp +++ b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp @@ -37,13 +37,9 @@ using namespace time_literals; DifferentialPosControl::DifferentialPosControl(ModuleParams *parent) : ModuleParams(parent) { - _rover_velocity_setpoint_pub.advertise(); - _rover_position_setpoint_pub.advertise(); _pure_pursuit_status_pub.advertise(); - - // Initially set to NaN to indicate that the rover has no position setpoint - _rover_position_setpoint.position_ned[0] = NAN; - _rover_position_setpoint.position_ned[1] = NAN; + _rover_position_setpoint_pub.advertise(); + _rover_velocity_setpoint_pub.advertise(); updateParams(); } @@ -65,6 +61,13 @@ void DifferentialPosControl::updatePosControl() if (_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { if (_vehicle_control_mode.flag_control_offboard_enabled) { generatePositionSetpoint(); + + } else if (_vehicle_control_mode.flag_control_manual_enabled && _vehicle_control_mode.flag_control_position_enabled) { + manualPositionMode(); + + } else if (_vehicle_control_mode.flag_control_auto_enabled) { + autoPositionMode(); + } generateVelocitySetpoint(); @@ -120,10 +123,13 @@ void DifferentialPosControl::generatePositionSetpoint() // Translate trajectory setpoint to rover position setpoint rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = _timestamp; + rover_position_setpoint.timestamp = hrt_absolute_time(); rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; - rover_position_setpoint.cruising_speed = _param_ro_speed_limit.get(); + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.cruising_speed = NAN; + rover_position_setpoint.arrival_speed = NAN; rover_position_setpoint.yaw = NAN; _rover_position_setpoint_pub.publish(rover_position_setpoint); @@ -131,15 +137,50 @@ void DifferentialPosControl::generatePositionSetpoint() void DifferentialPosControl::generateVelocitySetpoint() { - if (_vehicle_control_mode.flag_control_manual_enabled && _vehicle_control_mode.flag_control_position_enabled) { - manualPositionMode(); + if (_rover_position_setpoint_sub.updated()) { + _rover_position_setpoint_sub.copy(&_rover_position_setpoint); + _start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]); + _start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned; + } - } else if (_vehicle_control_mode.flag_control_auto_enabled) { - autoPositionMode(); + const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]); + float distance_to_target = target_waypoint_ned.isAllFinite() ? (target_waypoint_ned - _curr_pos_ned).norm() : NAN; - } else if (_rover_position_setpoint_sub.copy(&_rover_position_setpoint) - && PX4_ISFINITE(_rover_position_setpoint.position_ned[0]) && PX4_ISFINITE(_rover_position_setpoint.position_ned[1])) { - goToPositionMode(); + if (PX4_ISFINITE(distance_to_target) && distance_to_target > _param_nav_acc_rad.get()) { + + float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : + 0.f; + const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _param_nav_acc_rad.get() : + distance_to_target; + float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), + _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); + speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); + + if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { + speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, + fabsf(_rover_position_setpoint.cruising_speed)); + } + + pure_pursuit_status_s pure_pursuit_status{}; + pure_pursuit_status.timestamp = _timestamp; + + const float yaw_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), + _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, + _curr_pos_ned, fabsf(speed_setpoint)); + _pure_pursuit_status_pub.publish(pure_pursuit_status); + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = _timestamp; + rover_velocity_setpoint.speed = speed_setpoint; + rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? yaw_setpoint : matrix::wrap_pi( + yaw_setpoint + M_PI_F); + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + } else { + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = _timestamp; + rover_velocity_setpoint.speed = 0.f; + rover_velocity_setpoint.bearing = _vehicle_yaw; + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); } } @@ -156,29 +197,28 @@ void DifferentialPosControl::manualPositionMode() const float bearing_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -bearing_scaling, bearing_scaling); - if (fabsf(speed_setpoint) < FLT_EPSILON) { // Turn on spot - _course_control = false; - const float bearing_setpoint = matrix::wrap_pi(_vehicle_yaw + bearing_delta); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = 0.f; - rover_velocity_setpoint.bearing = bearing_setpoint; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } else if (fabsf(bearing_delta) > FLT_EPSILON) { // Closed loop yaw rate control - _course_control = false; - const float bearing_setpoint = matrix::wrap_pi(_vehicle_yaw + bearing_delta); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = bearing_setpoint; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + if (fabsf(bearing_delta) > FLT_EPSILON || fabsf(speed_setpoint) < FLT_EPSILON) { + _pos_ctl_course_direction = Vector2f(NAN, NAN); + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover + const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + bearing_delta); + const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); + const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * + pos_ctl_course_direction; + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); } else { // Course control if the steering input is zero (keep driving on a straight line) - if (!_course_control) { + if (!_pos_ctl_course_direction.isAllFinite()) { _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); _pos_ctl_start_position_ned = _curr_pos_ned; - _course_control = true; } // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover @@ -186,18 +226,16 @@ void DifferentialPosControl::manualPositionMode() const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * vector_scaling * _pos_ctl_course_direction; - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = _timestamp; - const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _pos_ctl_start_position_ned, - _curr_pos_ned, fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi( - bearing_setpoint + M_PI_F); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); + rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); } } @@ -216,107 +254,41 @@ void DifferentialPosControl::autoPositionMode() // Waypoint cruising speed _cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain( position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get(); + + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = _curr_wp_ned(0); + rover_position_setpoint.position_ned[1] = _curr_wp_ned(1); + rover_position_setpoint.start_ned[0] = _prev_wp_ned(0); + rover_position_setpoint.start_ned[1] = _prev_wp_ned(1); + rover_position_setpoint.arrival_speed = autoArrivalSpeed(_cruising_speed, _waypoint_transition_angle, + _param_ro_speed_limit.get(), _param_rd_trans_drv_trn.get(), _param_rd_miss_spd_gain.get(), _curr_wp_type); + rover_position_setpoint.cruising_speed = _cruising_speed; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); } - - // Distances to waypoints - const float distance_to_curr_wp = sqrt(powf(_curr_pos_ned(0) - _curr_wp_ned(0), - 2) + powf(_curr_pos_ned(1) - _curr_wp_ned(1), 2)); - - // Check stopping conditions - bool auto_stop{false}; - - if (_curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND - || _curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE - || !_next_wp_ned.isAllFinite()) { // Check stopping conditions - auto_stop = distance_to_curr_wp < _param_nav_acc_rad.get(); - } - - if (auto_stop) { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = 0.f; - rover_velocity_setpoint.bearing = _vehicle_yaw; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } else { - const float speed_setpoint = calcSpeedSetpoint(_cruising_speed, distance_to_curr_wp, _param_ro_decel_limit.get(), - _param_ro_jerk_limit.get(), _waypoint_transition_angle, _param_ro_speed_limit.get(), _param_rd_trans_drv_trn.get(), - _param_rd_miss_spd_gain.get(), _curr_wp_type); - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = _timestamp; - const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), _curr_wp_ned, _prev_wp_ned, _curr_pos_ned, - fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = bearing_setpoint; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - } - } -float DifferentialPosControl::calcSpeedSetpoint(const float cruising_speed, const float distance_to_curr_wp, - const float max_decel, const float max_jerk, const float waypoint_transition_angle, const float max_speed, - const float trans_drv_trn, const float miss_spd_gain, int curr_wp_type) +float DifferentialPosControl::autoArrivalSpeed(const float cruising_speed, const float waypoint_transition_angle, + const float max_speed, const float trans_drv_trn, const float miss_spd_gain, int curr_wp_type) { // Upcoming stop - if (max_decel > FLT_EPSILON && max_jerk > FLT_EPSILON && (!PX4_ISFINITE(waypoint_transition_angle) - || _waypoint_transition_angle < M_PI_F - trans_drv_trn || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE)) { - const float straight_line_speed = math::trajectory::computeMaxSpeedFromDistance(max_jerk, - max_decel, distance_to_curr_wp, 0.f); - return math::min(straight_line_speed, cruising_speed); + if (!PX4_ISFINITE(waypoint_transition_angle) || waypoint_transition_angle < M_PI_F - trans_drv_trn + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { + return 0.f; } // Straight line speed - if (max_jerk > FLT_EPSILON && max_decel > FLT_EPSILON && miss_spd_gain > FLT_EPSILON) { - const float speed_reduction = math::constrain(miss_spd_gain * math::interpolate(M_PI_F - _waypoint_transition_angle, + if (miss_spd_gain > FLT_EPSILON) { + const float speed_reduction = math::constrain(miss_spd_gain * math::interpolate(M_PI_F - waypoint_transition_angle, 0.f, M_PI_F, 0.f, 1.f), 0.f, 1.f); - const float straight_line_speed = math::trajectory::computeMaxSpeedFromDistance(max_jerk, max_decel, - distance_to_curr_wp, - max_speed * (1.f - speed_reduction)); - return math::min(straight_line_speed, cruising_speed); + return max_speed * (1.f - speed_reduction); } return cruising_speed; // Fallthrough } -void DifferentialPosControl::goToPositionMode() -{ - const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]); - const float distance_to_target = (target_waypoint_ned - _curr_pos_ned).norm(); - - if (distance_to_target > _param_nav_acc_rad.get()) { - float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), - _param_ro_decel_limit.get(), distance_to_target, 0.f); - const float max_speed = PX4_ISFINITE(_rover_position_setpoint.cruising_speed) ? - _rover_position_setpoint.cruising_speed : - _param_ro_speed_limit.get(); - speed_setpoint = math::min(speed_setpoint, max_speed); - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = _timestamp; - const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _curr_pos_ned, - _curr_pos_ned, fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = bearing_setpoint; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } else { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = 0.f; - rover_velocity_setpoint.bearing = _vehicle_yaw; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - } -} - bool DifferentialPosControl::runSanityChecks() { bool ret = true; diff --git a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp index 4cf34ac7f3..88ca5bb500 100644 --- a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp +++ b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp @@ -50,7 +50,6 @@ #include #include #include -#include #include #include #include @@ -98,35 +97,24 @@ private: void generatePositionSetpoint(); /** - * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint (Position Mode) or - * positionSetpointTriplet (Auto Mode) or roverPositionSetpoint. + * @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint. */ void generateVelocitySetpoint(); /** - * @brief Generate and publish roverVelocitySetpoint from manualControlSetpoint. + * @brief Generate and publish roverPositionSetpoint from manualControlSetpoint. */ void manualPositionMode(); /** - * @brief Generate and publish roverVelocitySetpoint from positionSetpointTriplet. + * @brief Generate and publish roverPositionSetpoint from positionSetpointTriplet. */ void autoPositionMode(); /** - * @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint. - */ - void goToPositionMode(); - - /** - * @brief Calculate the speed setpoint. During waypoint transition the speed is restricted to + * @brief Calculate the speed at which the rover should arrive at the current waypoint. During waypoint transition the speed is restricted to * Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN). - * On straight lines it is based on a speed trajectory such that the rover will arrive at the next waypoint transition - * with the desired waypoiny transition speed under consideration of the maximum deceleration and jerk. * @param cruising_speed Cruising speed [m/s]. - * @param distance_to_curr_wp Distance to the current waypoint [m]. - * @param max_decel Maximum allowed deceleration [m/s^2]. - * @param max_jerk Maximum allowed jerk [m/s^3]. * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] * @param max_speed Maximum speed setpoint [m/s] * @param trans_drv_trn Heading error threshold to switch from driving to turning [rad]. @@ -134,9 +122,8 @@ private: * @param curr_wp_type Type of the current waypoint. * @return Speed setpoint [m/s]. */ - float calcSpeedSetpoint(float cruising_speed, float distance_to_curr_wp, float max_decel, float max_jerk, - float waypoint_transition_angle, float max_speed, float trans_drv_trn, float miss_spd_gain, int curr_wp_type); - + float autoArrivalSpeed(const float cruising_speed, const float waypoint_transition_angle, const float max_speed, + const float trans_drv_trn, const float miss_spd_gain, int curr_wp_type); /** * @brief Check if the necessary parameters are set. @@ -160,7 +147,6 @@ private: // uORB publications - uORB::Publication _rover_velocity_status_pub{ORB_ID(rover_velocity_status)}; uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; uORB::Publication _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)}; uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; @@ -169,6 +155,7 @@ private: hrt_abstime _timestamp{0}; Quatf _vehicle_attitude_quaternion{}; Vector2f _curr_pos_ned{}; + Vector2f _start_ned{}; Vector2f _pos_ctl_course_direction{}; Vector2f _pos_ctl_start_position_ned{}; float _vehicle_speed{0.f}; // [m/s] Positiv: Forwards, Negativ: Backwards @@ -176,7 +163,6 @@ private: float _max_yaw_rate{0.f}; float _dt{0.f}; int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE}; - bool _course_control{false}; // Indicates if the rover is doing course control in manual position mode. bool _prev_param_check_passed{true}; // Waypoint variables From 38bcc501273acc6b934059281c3c1bfd4a3bb481 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 6 May 2025 13:44:49 +0200 Subject: [PATCH 065/130] differential: centralize mode management, resets and checks --- src/modules/rover_differential/CMakeLists.txt | 4 + .../DifferentialActControl.cpp | 15 - .../DifferentialActControl.hpp | 10 +- .../DifferentialAttControl.cpp | 132 ++------- .../DifferentialAttControl.hpp | 62 ++-- .../DifferentialDriveModes/CMakeLists.txt | 36 +++ .../DifferentialAutoMode/CMakeLists.txt | 38 +++ .../DifferentialAutoMode.cpp | 113 ++++++++ .../DifferentialAutoMode.hpp | 101 +++++++ .../DifferentialManualMode/CMakeLists.txt | 38 +++ .../DifferentialManualMode.cpp | 219 +++++++++++++++ .../DifferentialManualMode.hpp | 130 +++++++++ .../DifferentialOffboardMode/CMakeLists.txt | 38 +++ .../DifferentialOffboardMode.cpp | 92 ++++++ .../DifferentialOffboardMode.hpp | 89 ++++++ .../DifferentialPosControl.cpp | 265 +++--------------- .../DifferentialPosControl.hpp | 91 +----- .../DifferentialRateControl.cpp | 127 ++------- .../DifferentialRateControl.hpp | 56 +--- .../DifferentialVelControl.cpp | 124 +++----- .../DifferentialVelControl.hpp | 51 ++-- .../rover_differential/RoverDifferential.cpp | 127 ++++++++- .../rover_differential/RoverDifferential.hpp | 47 +++- 23 files changed, 1248 insertions(+), 757 deletions(-) create mode 100644 src/modules/rover_differential/DifferentialDriveModes/CMakeLists.txt create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/CMakeLists.txt create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.cpp create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.hpp create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/CMakeLists.txt create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.cpp create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.hpp create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/CMakeLists.txt create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.cpp create mode 100644 src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.hpp diff --git a/src/modules/rover_differential/CMakeLists.txt b/src/modules/rover_differential/CMakeLists.txt index ebae1e8723..05aef49cfe 100644 --- a/src/modules/rover_differential/CMakeLists.txt +++ b/src/modules/rover_differential/CMakeLists.txt @@ -36,6 +36,7 @@ add_subdirectory(DifferentialRateControl) add_subdirectory(DifferentialAttControl) add_subdirectory(DifferentialVelControl) add_subdirectory(DifferentialPosControl) +add_subdirectory(DifferentialDriveModes) px4_add_module( MODULE modules__rover_differential @@ -49,6 +50,9 @@ px4_add_module( DifferentialAttControl DifferentialVelControl DifferentialPosControl + DifferentialAutoMode + DifferentialManualMode + DifferentialOffboardMode px4_work_queue rover_control pure_pursuit diff --git a/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp index dd9c8c99e0..c9b67b0b6c 100644 --- a/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp +++ b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.cpp @@ -99,21 +99,6 @@ Vector2f DifferentialActControl::computeInverseKinematics(float throttle, const throttle + speed_diff_normalized); } -void DifferentialActControl::manualManualMode() -{ - manual_control_setpoint_s manual_control_setpoint{}; - _manual_control_setpoint_sub.copy(&manual_control_setpoint); - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = hrt_absolute_time(); - rover_steering_setpoint.normalized_speed_diff = manual_control_setpoint.roll; - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = hrt_absolute_time(); - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); -} - void DifferentialActControl::stopVehicle() { actuator_motors_s actuator_motors{}; diff --git a/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp index ff893fbfbb..2076542e4a 100644 --- a/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp +++ b/src/modules/rover_differential/DifferentialActControl/DifferentialActControl.hpp @@ -67,11 +67,6 @@ public: */ void updateActControl(); - /** - * @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint. - */ - void manualManualMode(); - /** * @brief Stop the vehicle by sending 0 commands to motors and servos. */ @@ -96,12 +91,9 @@ private: uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)}; uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; // uORB publications - uORB::Publication _actuator_motors_pub{ORB_ID(actuator_motors)}; - uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; + uORB::Publication _actuator_motors_pub{ORB_ID(actuator_motors)}; // Variables hrt_abstime _timestamp{0}; diff --git a/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.cpp b/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.cpp index 5bc9ab380a..99217341d7 100644 --- a/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.cpp +++ b/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.cpp @@ -38,8 +38,6 @@ using namespace time_literals; DifferentialAttControl::DifferentialAttControl(ModuleParams *parent) : ModuleParams(parent) { _rover_rate_setpoint_pub.advertise(); - _rover_throttle_setpoint_pub.advertise(); - _rover_attitude_setpoint_pub.advertise(); _rover_attitude_status_pub.advertise(); updateParams(); } @@ -52,21 +50,20 @@ void DifferentialAttControl::updateParams() _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; } + // Set up PID controller _pid_yaw.setGains(_param_ro_yaw_p.get(), 0.f, 0.f); _pid_yaw.setIntegralLimit(_max_yaw_rate); _pid_yaw.setOutputLimit(_max_yaw_rate); + + // Set up slew rate _adjusted_yaw_setpoint.setSlewRate(_max_yaw_rate); } void DifferentialAttControl::updateAttControl() { - const hrt_abstime timestamp_prev = _timestamp; + hrt_abstime timestamp_prev = _timestamp; _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); - } + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; if (_vehicle_attitude_sub.updated()) { vehicle_attitude_s vehicle_attitude{}; @@ -75,17 +72,20 @@ void DifferentialAttControl::updateAttControl() _vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); } - if (_vehicle_control_mode.flag_control_attitude_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { + if (_rover_attitude_setpoint_sub.updated()) { + rover_attitude_setpoint_s rover_attitude_setpoint{}; + _rover_attitude_setpoint_sub.copy(&rover_attitude_setpoint); + _yaw_setpoint = rover_attitude_setpoint.yaw_setpoint; + } - if (_vehicle_control_mode.flag_control_manual_enabled || _vehicle_control_mode.flag_control_offboard_enabled) { - generateAttitudeAndThrottleSetpoint(); - } + if (PX4_ISFINITE(_yaw_setpoint)) { + const float yaw_rate_setpoint = RoverControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, _max_yaw_rate, + _vehicle_yaw, _yaw_setpoint, dt); + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = _timestamp; + rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate); + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); - generateRateSetpoint(); - - } else { // Reset pid and slew rate when attitude control is not active - _pid_yaw.resetIntegral(); - _adjusted_yaw_setpoint.setForcedValue(0.f); } // Publish attitude controller status (logging only) @@ -97,96 +97,6 @@ void DifferentialAttControl::updateAttControl() } -void DifferentialAttControl::generateAttitudeAndThrottleSetpoint() -{ - const bool stab_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled - && !_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_control_attitude_enabled; - - if (stab_mode_enabled && _manual_control_setpoint_sub.updated()) { // Stab Mode - manual_control_setpoint_s manual_control_setpoint{}; - - if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - - const float yaw_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate / _param_ro_yaw_p.get(), - _max_yaw_rate / _param_ro_yaw_p.get()); - - if (fabsf(yaw_delta) > FLT_EPSILON - || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { // Closed loop yaw rate control - _stab_yaw_ctl = false; - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + yaw_delta); - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = yaw_setpoint; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - - } else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw) - if (!_stab_yaw_ctl) { - _stab_yaw_setpoint = _vehicle_yaw; - _stab_yaw_ctl = true; - } - - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } - - - } - - } else if (_vehicle_control_mode.flag_control_offboard_enabled) { // Offboard attitude control - trajectory_setpoint_s trajectory_setpoint{}; - _trajectory_setpoint_sub.copy(&trajectory_setpoint); - - if (_offboard_control_mode_sub.updated()) { - _offboard_control_mode_sub.copy(&_offboard_control_mode); - } - - const bool offboard_att_control = _offboard_control_mode.attitude && !_offboard_control_mode.position - && !_offboard_control_mode.velocity; - - if (offboard_att_control && PX4_ISFINITE(trajectory_setpoint.yaw)) { - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = trajectory_setpoint.yaw; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } - } -} - -void DifferentialAttControl::generateRateSetpoint() -{ - if (_rover_attitude_setpoint_sub.updated()) { - _rover_attitude_setpoint_sub.copy(&_rover_attitude_setpoint); - } - - if (_rover_rate_setpoint_sub.updated()) { - _rover_rate_setpoint_sub.copy(&_rover_rate_setpoint); - } - - // Check if a new rate setpoint was already published from somewhere else - if (_rover_rate_setpoint.timestamp > _last_rate_setpoint_update - && _rover_rate_setpoint.timestamp > _rover_attitude_setpoint.timestamp) { - return; - } - - const float yaw_rate_setpoint = RoverControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, _max_yaw_rate, - _vehicle_yaw, _rover_attitude_setpoint.yaw_setpoint, _dt); - - _last_rate_setpoint_update = _timestamp; - rover_rate_setpoint_s rover_rate_setpoint{}; - rover_rate_setpoint.timestamp = _timestamp; - rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate); - _rover_rate_setpoint_pub.publish(rover_rate_setpoint); -} - bool DifferentialAttControl::runSanityChecks() { bool ret = true; @@ -197,13 +107,9 @@ bool DifferentialAttControl::runSanityChecks() if (_param_ro_yaw_p.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("differential_att_control_conf_invalid_yaw_p"), events::Log::Error, - "Invalid configuration of necessary parameter RO_YAW_P", _param_ro_yaw_p.get()); - } + events::send(events::ID("differential_att_control_conf_invalid_yaw_p"), events::Log::Error, + "Invalid configuration of necessary parameter RO_YAW_P", _param_ro_yaw_p.get()); } - _prev_param_check_passed = ret; return ret; } diff --git a/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.hpp b/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.hpp index 82087f8278..205d1d3d0e 100644 --- a/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.hpp +++ b/src/modules/rover_differential/DifferentialAttControl/DifferentialAttControl.hpp @@ -48,15 +48,9 @@ #include #include #include -#include -#include -#include +#include #include #include -#include -#include -#include -#include /** * @brief Class for differential attitude control. @@ -72,10 +66,21 @@ public: ~DifferentialAttControl() = default; /** - * @brief Update attitude controller. + * @brief Generate and publish roverRateSetpoint from roverAttitudeSetpoint. */ void updateAttControl(); + /** + * @brief Reset attitude controller. + */ + void reset() {_pid_yaw.resetIntegral(); _yaw_setpoint = NAN;}; + + /** + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. + */ + bool runSanityChecks(); + protected: /** * @brief Update the parameters of the module. @@ -83,52 +88,19 @@ protected: void updateParams() override; private: - /** - * @brief Generate and publish roverAttitudeSetpoint and roverThrottleSetpoint from manualControlSetpoint (Stab Mode) - * or trajectorySetpoint (Offboard attitude control). - */ - void generateAttitudeAndThrottleSetpoint(); - - /** - * @brief Generate and publish roverRateSetpoint from roverAttitudeSetpoint. - */ - void generateRateSetpoint(); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); - // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; - uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; uORB::Subscription _rover_attitude_setpoint_sub{ORB_ID(rover_attitude_setpoint)}; - uORB::Subscription _rover_rate_setpoint_sub{ORB_ID(rover_rate_setpoint)}; - vehicle_control_mode_s _vehicle_control_mode{}; - rover_attitude_setpoint_s _rover_attitude_setpoint{}; - rover_rate_setpoint_s _rover_rate_setpoint{}; - offboard_control_mode_s _offboard_control_mode{}; // uORB publications - uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; - uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; - uORB::Publication _rover_attitude_status_pub{ORB_ID(rover_attitude_status)}; + uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; + uORB::Publication _rover_attitude_status_pub{ORB_ID(rover_attitude_status)}; // Variables - hrt_abstime _timestamp{0}; - hrt_abstime _last_rate_setpoint_update{0}; float _vehicle_yaw{0.f}; - float _dt{0.f}; + hrt_abstime _timestamp{0}; float _max_yaw_rate{0.f}; - float _stab_yaw_setpoint{0.f}; // Yaw setpoint if rover is doing yaw control in stab mode - bool _stab_yaw_ctl{false}; // Indicates if rover is doing yaw control in stab mode - bool _prev_param_check_passed{true}; + float _yaw_setpoint{NAN}; // Controllers PID _pid_yaw; diff --git a/src/modules/rover_differential/DifferentialDriveModes/CMakeLists.txt b/src/modules/rover_differential/DifferentialDriveModes/CMakeLists.txt new file mode 100644 index 0000000000..66fcb084b0 --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(DifferentialAutoMode) +add_subdirectory(DifferentialManualMode) +add_subdirectory(DifferentialOffboardMode) diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/CMakeLists.txt b/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/CMakeLists.txt new file mode 100644 index 0000000000..cce9baecc3 --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(DifferentialAutoMode +DifferentialAutoMode.cpp +) + +target_include_directories(DifferentialAutoMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.cpp b/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.cpp new file mode 100644 index 0000000000..bf3e4bf98b --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.cpp @@ -0,0 +1,113 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "DifferentialAutoMode.hpp" + +using namespace time_literals; + +DifferentialAutoMode::DifferentialAutoMode(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_position_setpoint_pub.advertise(); +} + +void DifferentialAutoMode::updateParams() +{ + ModuleParams::updateParams(); +} + +void DifferentialAutoMode::autoControl() +{ + if (_position_setpoint_triplet_sub.updated()) { + position_setpoint_triplet_s position_setpoint_triplet{}; + _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); + int curr_wp_type = position_setpoint_triplet.current.type; + + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + + MapProjection global_ned_proj_ref{}; + + if (!global_ned_proj_ref.isInitialized() + || (global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { + global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, + vehicle_local_position.ref_timestamp); + } + + Vector2f curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); + Vector2f curr_wp_ned{NAN, NAN}; + Vector2f prev_wp_ned{NAN, NAN}; + Vector2f next_wp_ned{NAN, NAN}; + + RoverControl::globalToLocalSetpointTriplet(curr_wp_ned, prev_wp_ned, next_wp_ned, position_setpoint_triplet, + curr_pos_ned, global_ned_proj_ref); + + float waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned); + + // Waypoint cruising speed + float cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain( + position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get(); + + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = curr_wp_ned(0); + rover_position_setpoint.position_ned[1] = curr_wp_ned(1); + rover_position_setpoint.start_ned[0] = prev_wp_ned(0); + rover_position_setpoint.start_ned[1] = prev_wp_ned(1); + rover_position_setpoint.arrival_speed = arrivalSpeed(cruising_speed, waypoint_transition_angle, + _param_ro_speed_limit.get(), _param_rd_trans_drv_trn.get(), _param_rd_miss_spd_gain.get(), curr_wp_type); + rover_position_setpoint.cruising_speed = cruising_speed; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + } +} + +float DifferentialAutoMode::arrivalSpeed(const float cruising_speed, const float waypoint_transition_angle, + const float max_speed, const float trans_drv_trn, const float miss_spd_gain, int curr_wp_type) +{ + // Upcoming stop + if (!PX4_ISFINITE(waypoint_transition_angle) || waypoint_transition_angle < M_PI_F - trans_drv_trn + || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { + return 0.f; + } + + // Straight line speed + if (miss_spd_gain > FLT_EPSILON) { + const float speed_reduction = math::constrain(miss_spd_gain * math::interpolate(M_PI_F - waypoint_transition_angle, + 0.f, M_PI_F, 0.f, 1.f), 0.f, 1.f); + return max_speed * (1.f - speed_reduction); + } + + return cruising_speed; // Fallthrough + +} diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.hpp b/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.hpp new file mode 100644 index 0000000000..72e5259cb2 --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.hpp @@ -0,0 +1,101 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include + +// uORB includes +#include +#include +#include +#include +#include + +/** + * @brief Class for differential auto mode. + */ +class DifferentialAutoMode : public ModuleParams +{ +public: + /** + * @brief Constructor for auto mode. + * @param parent The parent ModuleParams object. + */ + DifferentialAutoMode(ModuleParams *parent); + ~DifferentialAutoMode() = default; + + /** + * @brief Generate and publish roverPositionSetpoint from positionSetpointTriplet. + */ + void autoControl(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + /** + * @brief Calculate the speed at which the rover should arrive at the current waypoint. During waypoint transition the speed is restricted to + * Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN). + * @param cruising_speed Cruising speed [m/s]. + * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] + * @param max_speed Maximum speed setpoint [m/s] + * @param trans_drv_trn Heading error threshold to switch from driving to turning [rad]. + * @param miss_spd_gain Tuning parameter for the speed reduction during waypoint transition. + * @param curr_wp_type Type of the current waypoint. + * @return Speed setpoint [m/s]. + */ + float arrivalSpeed(const float cruising_speed, const float waypoint_transition_angle, const float max_speed, + const float trans_drv_trn, const float miss_spd_gain, int curr_wp_type); + + // uORB subscriptions + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; + + // uORB publications + uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_ro_speed_limit, + (ParamFloat) _param_rd_trans_drv_trn, + (ParamFloat) _param_rd_miss_spd_gain + ) +}; diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/CMakeLists.txt b/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/CMakeLists.txt new file mode 100644 index 0000000000..b5323230ff --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(DifferentialManualMode + DifferentialManualMode.cpp +) + +target_include_directories(DifferentialManualMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.cpp b/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.cpp new file mode 100644 index 0000000000..99f8f8e2d0 --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.cpp @@ -0,0 +1,219 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "DifferentialManualMode.hpp" + +using namespace time_literals; + +DifferentialManualMode::DifferentialManualMode(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_throttle_setpoint_pub.advertise(); + _rover_steering_setpoint_pub.advertise(); + _rover_rate_setpoint_pub.advertise(); + _rover_attitude_setpoint_pub.advertise(); + _rover_velocity_setpoint_pub.advertise(); + _rover_position_setpoint_pub.advertise(); +} + +void DifferentialManualMode::updateParams() +{ + ModuleParams::updateParams(); + _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; +} + +void DifferentialManualMode::manual() +{ + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = hrt_absolute_time(); + rover_steering_setpoint.normalized_speed_diff = manual_control_setpoint.roll; + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); +} + +void DifferentialManualMode::acro() +{ + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = math::interpolate(manual_control_setpoint.roll, -1.f, 1.f, + -_max_yaw_rate, _max_yaw_rate); + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); +} + +void DifferentialManualMode::stab() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + matrix::Quatf vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); + } + + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = hrt_absolute_time(); + rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); + + if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON + || fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) { + _stab_yaw_setpoint = NAN; + + // Rate control + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate);; + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); + + // Set uncontrolled setpoint invalid + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = NAN; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + + } else { // Heading control + if (!PX4_ISFINITE(_stab_yaw_setpoint)) { + _stab_yaw_setpoint = _vehicle_yaw; + } + + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + } +} + +void DifferentialManualMode::position() +{ + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + matrix::Quatf vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); + } + + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); + } + + manual_control_setpoint_s manual_control_setpoint{}; + _manual_control_setpoint_sub.copy(&manual_control_setpoint); + + const float speed_setpoint = math::interpolate(manual_control_setpoint.throttle, + -1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); + + if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON + || fabsf(speed_setpoint) < FLT_EPSILON) { + _pos_ctl_course_direction = Vector2f(NAN, NAN); + + // Speed control + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = hrt_absolute_time(); + rover_velocity_setpoint.speed = speed_setpoint; + rover_velocity_setpoint.bearing = NAN; + rover_velocity_setpoint.yaw = NAN; + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + // Rate control + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = math::interpolate(math::deadzone(manual_control_setpoint.roll, + _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate);; + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); + + // Set uncontrolled setpoints invalid + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = NAN; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = NAN; + rover_position_setpoint.position_ned[1] = NAN; + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = NAN; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + + } else { // Course control + if (!_pos_ctl_course_direction.isAllFinite()) { + _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); + _pos_ctl_start_position_ned = _curr_pos_ned; + } + + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover + const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned; + const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); + const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * + vector_scaling * _pos_ctl_course_direction; + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); + rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); + rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); + rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.cruising_speed = speed_setpoint; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + } +} + +void DifferentialManualMode::reset() +{ + _stab_yaw_setpoint = NAN; + _pos_ctl_course_direction = Vector2f(NAN, NAN); + _pos_ctl_start_position_ned = Vector2f(NAN, NAN); + _curr_pos_ned = Vector2f(NAN, NAN); +} diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.hpp b/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.hpp new file mode 100644 index 0000000000..bce5d36ea5 --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.hpp @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace matrix; + +/** + * @brief Class for differential manual mode. + */ +class DifferentialManualMode : public ModuleParams +{ +public: + /** + * @brief Constructor for DifferentialManualMode. + * @param parent The parent ModuleParams object. + */ + DifferentialManualMode(ModuleParams *parent); + ~DifferentialManualMode() = default; + + /** + * @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint. + */ + void manual(); + + /** + * @brief Generate and publish roverThrottleSetpoint/RoverRateSetpoint from manualControlSetpoint. + */ + void acro(); + + /** + * @brief Generate and publish roverSetpoints from manualControlSetpoint. + */ + void stab(); + + /** + * @brief Generate and publish roverSetpoints from manualControlSetpoint. + */ + void position(); + + /** + * @brief Reset manual mode variables. + */ + void reset(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + // uORB subscriptions + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + + // uORB publications + uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; + uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; + uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; + uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; + uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; + uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; + + // Variables + Vector2f _pos_ctl_course_direction{NAN, NAN}; + Vector2f _pos_ctl_start_position_ned{NAN, NAN}; + Vector2f _curr_pos_ned{NAN, NAN}; + float _stab_yaw_setpoint{NAN}; + float _vehicle_yaw{NAN}; + float _max_yaw_rate{NAN}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_ro_yaw_rate_limit, + (ParamFloat) _param_ro_yaw_stick_dz, + (ParamFloat) _param_pp_lookahd_max, + (ParamFloat) _param_ro_speed_limit + ) +}; diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/CMakeLists.txt b/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/CMakeLists.txt new file mode 100644 index 0000000000..8e782323bd --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(DifferentialOffboardMode + DifferentialOffboardMode.cpp +) + +target_include_directories(DifferentialOffboardMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.cpp b/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.cpp new file mode 100644 index 0000000000..eca17e18ff --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.cpp @@ -0,0 +1,92 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "DifferentialOffboardMode.hpp" + +using namespace time_literals; + +DifferentialOffboardMode::DifferentialOffboardMode(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_rate_setpoint_pub.advertise(); + _rover_attitude_setpoint_pub.advertise(); + _rover_velocity_setpoint_pub.advertise(); + _rover_position_setpoint_pub.advertise(); +} + +void DifferentialOffboardMode::updateParams() +{ + ModuleParams::updateParams(); +} + +void DifferentialOffboardMode::offboardControl() +{ + offboard_control_mode_s offboard_control_mode{}; + _offboard_control_mode_sub.copy(&offboard_control_mode); + + trajectory_setpoint_s trajectory_setpoint{}; + _trajectory_setpoint_sub.copy(&trajectory_setpoint); + + if (offboard_control_mode.position) { + rover_position_setpoint_s rover_position_setpoint{}; + rover_position_setpoint.timestamp = hrt_absolute_time(); + rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; + rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; + rover_position_setpoint.start_ned[0] = NAN; + rover_position_setpoint.start_ned[1] = NAN; + rover_position_setpoint.cruising_speed = NAN; + rover_position_setpoint.arrival_speed = NAN; + rover_position_setpoint.yaw = NAN; + _rover_position_setpoint_pub.publish(rover_position_setpoint); + + } else if (offboard_control_mode.velocity) { + const Vector2f velocity_ned(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]); + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = hrt_absolute_time(); + rover_velocity_setpoint.speed = velocity_ned.norm(); + rover_velocity_setpoint.bearing = atan2f(velocity_ned(1), velocity_ned(0)); + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + } else if (offboard_control_mode.attitude) { + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = hrt_absolute_time(); + rover_attitude_setpoint.yaw_setpoint = trajectory_setpoint.yaw; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + + } else if (offboard_control_mode.body_rate) { + rover_rate_setpoint_s rover_rate_setpoint{}; + rover_rate_setpoint.timestamp = hrt_absolute_time(); + rover_rate_setpoint.yaw_rate_setpoint = trajectory_setpoint.yawspeed; + _rover_rate_setpoint_pub.publish(rover_rate_setpoint); + } +} diff --git a/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.hpp b/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.hpp new file mode 100644 index 0000000000..ebdeef0112 --- /dev/null +++ b/src/modules/rover_differential/DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.hpp @@ -0,0 +1,89 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// Libraries +#include +#include + +// uORB includes +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace matrix; + +/** + * @brief Class for differential manual mode. + */ +class DifferentialOffboardMode : public ModuleParams +{ +public: + /** + * @brief Constructor for DifferentialOffboardMode. + * @param parent The parent ModuleParams object. + */ + DifferentialOffboardMode(ModuleParams *parent); + ~DifferentialOffboardMode() = default; + + /** + * @brief Generate and publish roverSetpoints from trajectorySetpoint. + */ + void offboardControl(); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + // uORB subscriptions + uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; + uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; + + // uORB publications + uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; + uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; + uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; + uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; +}; diff --git a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp index 06363c42cb..52a5a00eeb 100644 --- a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp +++ b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.cpp @@ -38,7 +38,6 @@ using namespace time_literals; DifferentialPosControl::DifferentialPosControl(ModuleParams *parent) : ModuleParams(parent) { _pure_pursuit_status_pub.advertise(); - _rover_position_setpoint_pub.advertise(); _rover_velocity_setpoint_pub.advertise(); updateParams(); @@ -47,96 +46,14 @@ DifferentialPosControl::DifferentialPosControl(ModuleParams *parent) : ModulePar void DifferentialPosControl::updateParams() { ModuleParams::updateParams(); - _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; } void DifferentialPosControl::updatePosControl() { - const hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - updateSubscriptions(); - if (_vehicle_control_mode.flag_control_position_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { - if (_vehicle_control_mode.flag_control_offboard_enabled) { - generatePositionSetpoint(); + hrt_abstime timestamp = hrt_absolute_time(); - } else if (_vehicle_control_mode.flag_control_manual_enabled && _vehicle_control_mode.flag_control_position_enabled) { - manualPositionMode(); - - } else if (_vehicle_control_mode.flag_control_auto_enabled) { - autoPositionMode(); - - } - - generateVelocitySetpoint(); - - } - -} - -void DifferentialPosControl::updateSubscriptions() -{ - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); - } - - if (_vehicle_attitude_sub.updated()) { - vehicle_attitude_s vehicle_attitude{}; - _vehicle_attitude_sub.copy(&vehicle_attitude); - _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); - _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); - } - - if (_vehicle_local_position_sub.updated()) { - vehicle_local_position_s vehicle_local_position{}; - _vehicle_local_position_sub.copy(&vehicle_local_position); - - if (!_global_ned_proj_ref.isInitialized() - || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) { - _global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon, - vehicle_local_position.ref_timestamp); - } - - _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); - Vector3f velocity_ned(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz); - Vector3f velocity_xyz = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_ned); - Vector2f velocity_2d = Vector2f(velocity_xyz(0), velocity_xyz(1)); - _vehicle_speed = velocity_2d.norm() > _param_ro_speed_th.get() ? sign(velocity_2d(0)) * velocity_2d.norm() : 0.f; - } - -} - -void DifferentialPosControl::generatePositionSetpoint() -{ - if (_offboard_control_mode_sub.updated()) { - _offboard_control_mode_sub.copy(&_offboard_control_mode); - } - - if (!_offboard_control_mode.position) { - return; - } - - trajectory_setpoint_s trajectory_setpoint{}; - _trajectory_setpoint_sub.copy(&trajectory_setpoint); - - // Translate trajectory setpoint to rover position setpoint - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0]; - rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1]; - rover_position_setpoint.start_ned[0] = NAN; - rover_position_setpoint.start_ned[1] = NAN; - rover_position_setpoint.cruising_speed = NAN; - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - -} - -void DifferentialPosControl::generateVelocitySetpoint() -{ if (_rover_position_setpoint_sub.updated()) { _rover_position_setpoint_sub.copy(&_rover_position_setpoint); _start_ned = Vector2f(_rover_position_setpoint.start_ned[0], _rover_position_setpoint.start_ned[1]); @@ -144,163 +61,73 @@ void DifferentialPosControl::generateVelocitySetpoint() } const Vector2f target_waypoint_ned(_rover_position_setpoint.position_ned[0], _rover_position_setpoint.position_ned[1]); - float distance_to_target = target_waypoint_ned.isAllFinite() ? (target_waypoint_ned - _curr_pos_ned).norm() : NAN; - if (PX4_ISFINITE(distance_to_target) && distance_to_target > _param_nav_acc_rad.get()) { + if (target_waypoint_ned.isAllFinite()) { + float distance_to_target = (target_waypoint_ned - _curr_pos_ned).norm(); - float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : - 0.f; - const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _param_nav_acc_rad.get() : - distance_to_target; - float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), - _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); - speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); + if (distance_to_target > _param_nav_acc_rad.get()) { + float arrival_speed = PX4_ISFINITE(_rover_position_setpoint.arrival_speed) ? _rover_position_setpoint.arrival_speed : + 0.f; + const float distance = arrival_speed > 0.f + FLT_EPSILON ? distance_to_target - _param_nav_acc_rad.get() : + distance_to_target; + float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(), + _param_ro_decel_limit.get(), distance, fabsf(arrival_speed)); + speed_setpoint = math::min(speed_setpoint, _param_ro_speed_limit.get()); - if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { - speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, - fabsf(_rover_position_setpoint.cruising_speed)); + if (PX4_ISFINITE(_rover_position_setpoint.cruising_speed)) { + speed_setpoint = sign(_rover_position_setpoint.cruising_speed) * math::min(speed_setpoint, + fabsf(_rover_position_setpoint.cruising_speed)); + } + + pure_pursuit_status_s pure_pursuit_status{}; + pure_pursuit_status.timestamp = timestamp; + + const float yaw_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), + _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, + _curr_pos_ned, fabsf(speed_setpoint)); + _pure_pursuit_status_pub.publish(pure_pursuit_status); + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = timestamp; + rover_velocity_setpoint.speed = speed_setpoint; + rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? yaw_setpoint : matrix::wrap_pi( + yaw_setpoint + M_PI_F); + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); + + } else { + rover_velocity_setpoint_s rover_velocity_setpoint{}; + rover_velocity_setpoint.timestamp = timestamp; + rover_velocity_setpoint.speed = 0.f; + rover_velocity_setpoint.bearing = _vehicle_yaw; + _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); } - - pure_pursuit_status_s pure_pursuit_status{}; - pure_pursuit_status.timestamp = _timestamp; - - const float yaw_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(), - _param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), target_waypoint_ned, _start_ned, - _curr_pos_ned, fabsf(speed_setpoint)); - _pure_pursuit_status_pub.publish(pure_pursuit_status); - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = speed_setpoint; - rover_velocity_setpoint.bearing = speed_setpoint > -FLT_EPSILON ? yaw_setpoint : matrix::wrap_pi( - yaw_setpoint + M_PI_F); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - - } else { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = 0.f; - rover_velocity_setpoint.bearing = _vehicle_yaw; - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); } } -void DifferentialPosControl::manualPositionMode() +void DifferentialPosControl::updateSubscriptions() { - manual_control_setpoint_s manual_control_setpoint{}; - _manual_control_setpoint_sub.copy(&manual_control_setpoint); - - const float speed_setpoint = math::interpolate(manual_control_setpoint.throttle, - -1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); - const float bearing_scaling = math::min(_max_yaw_rate / _param_ro_yaw_p.get(), - _param_rd_trans_drv_trn.get() - FLT_EPSILON); - const float bearing_delta = math::interpolate(math::deadzone(manual_control_setpoint.roll, - _param_ro_yaw_stick_dz.get()), -1.f, 1.f, -bearing_scaling, bearing_scaling); - - if (fabsf(bearing_delta) > FLT_EPSILON || fabsf(speed_setpoint) < FLT_EPSILON) { - _pos_ctl_course_direction = Vector2f(NAN, NAN); - // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover - const float yaw_setpoint = matrix::wrap_pi(_vehicle_yaw + bearing_delta); - const Vector2f pos_ctl_course_direction = Vector2f(cos(yaw_setpoint), sin(yaw_setpoint)); - const Vector2f target_waypoint_ned = _curr_pos_ned + sign(speed_setpoint) * _param_pp_lookahd_max.get() * - pos_ctl_course_direction; - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); - rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); - rover_position_setpoint.start_ned[0] = NAN; - rover_position_setpoint.start_ned[1] = NAN; - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.cruising_speed = speed_setpoint; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - - } else { // Course control if the steering input is zero (keep driving on a straight line) - if (!_pos_ctl_course_direction.isAllFinite()) { - _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); - _pos_ctl_start_position_ned = _curr_pos_ned; - } - - // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover - const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned; - const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get(); - const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) * - vector_scaling * _pos_ctl_course_direction; - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = target_waypoint_ned(0); - rover_position_setpoint.position_ned[1] = target_waypoint_ned(1); - rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0); - rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1); - rover_position_setpoint.arrival_speed = NAN; - rover_position_setpoint.cruising_speed = speed_setpoint; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - } -} - -void DifferentialPosControl::autoPositionMode() -{ - if (_position_setpoint_triplet_sub.updated()) { - position_setpoint_triplet_s position_setpoint_triplet{}; - _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); - _curr_wp_type = position_setpoint_triplet.current.type; - - RoverControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet, - _curr_pos_ned, _global_ned_proj_ref); - - _waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned, _next_wp_ned); - - // Waypoint cruising speed - _cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain( - position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get(); - - rover_position_setpoint_s rover_position_setpoint{}; - rover_position_setpoint.timestamp = hrt_absolute_time(); - rover_position_setpoint.position_ned[0] = _curr_wp_ned(0); - rover_position_setpoint.position_ned[1] = _curr_wp_ned(1); - rover_position_setpoint.start_ned[0] = _prev_wp_ned(0); - rover_position_setpoint.start_ned[1] = _prev_wp_ned(1); - rover_position_setpoint.arrival_speed = autoArrivalSpeed(_cruising_speed, _waypoint_transition_angle, - _param_ro_speed_limit.get(), _param_rd_trans_drv_trn.get(), _param_rd_miss_spd_gain.get(), _curr_wp_type); - rover_position_setpoint.cruising_speed = _cruising_speed; - rover_position_setpoint.yaw = NAN; - _rover_position_setpoint_pub.publish(rover_position_setpoint); - } -} - -float DifferentialPosControl::autoArrivalSpeed(const float cruising_speed, const float waypoint_transition_angle, - const float max_speed, const float trans_drv_trn, const float miss_spd_gain, int curr_wp_type) -{ - // Upcoming stop - if (!PX4_ISFINITE(waypoint_transition_angle) || waypoint_transition_angle < M_PI_F - trans_drv_trn - || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND || curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) { - return 0.f; + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + matrix::Quatf vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi(); } - // Straight line speed - if (miss_spd_gain > FLT_EPSILON) { - const float speed_reduction = math::constrain(miss_spd_gain * math::interpolate(M_PI_F - waypoint_transition_angle, - 0.f, M_PI_F, 0.f, 1.f), 0.f, 1.f); - return max_speed * (1.f - speed_reduction); + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); } - return cruising_speed; // Fallthrough - } bool DifferentialPosControl::runSanityChecks() { bool ret = true; - if (_param_ro_yaw_rate_limit.get() < FLT_EPSILON) { - ret = false; - } - if (_param_ro_speed_limit.get() < FLT_EPSILON) { ret = false; } - _prev_param_check_passed = ret; return ret; } diff --git a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp index 88ca5bb500..52c5253ef7 100644 --- a/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp +++ b/src/modules/rover_differential/DifferentialPosControl/DifferentialPosControl.hpp @@ -41,7 +41,6 @@ #include #include #include -#include #include // uORB includes @@ -50,13 +49,7 @@ #include #include #include -#include -#include -#include #include -#include -#include -#include #include using namespace matrix; @@ -75,10 +68,16 @@ public: ~DifferentialPosControl() = default; /** - * @brief Update position controller. + * @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint. */ void updatePosControl(); + /** + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. + */ + bool runSanityChecks(); + protected: /** * @brief Update the parameters of the module. @@ -91,104 +90,28 @@ private: */ void updateSubscriptions(); - /** - * @brief Generate and publish roverPositionSetpoint from position of trajectorySetpoint. - */ - void generatePositionSetpoint(); - - /** - * @brief Generate and publish roverVelocitySetpoint from roverPositionSetpoint. - */ - void generateVelocitySetpoint(); - - /** - * @brief Generate and publish roverPositionSetpoint from manualControlSetpoint. - */ - void manualPositionMode(); - - /** - * @brief Generate and publish roverPositionSetpoint from positionSetpointTriplet. - */ - void autoPositionMode(); - - /** - * @brief Calculate the speed at which the rover should arrive at the current waypoint. During waypoint transition the speed is restricted to - * Maximum_speed * (1 - normalized_transition_angle * RM_MISS_VEL_GAIN). - * @param cruising_speed Cruising speed [m/s]. - * @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - * @param max_speed Maximum speed setpoint [m/s] - * @param trans_drv_trn Heading error threshold to switch from driving to turning [rad]. - * @param miss_spd_gain Tuning parameter for the speed reduction during waypoint transition. - * @param curr_wp_type Type of the current waypoint. - * @return Speed setpoint [m/s]. - */ - float autoArrivalSpeed(const float cruising_speed, const float waypoint_transition_angle, const float max_speed, - const float trans_drv_trn, const float miss_spd_gain, int curr_wp_type); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); - // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; - uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; - uORB::Subscription _rover_velocity_setpoint_sub{ORB_ID(rover_velocity_setpoint)}; uORB::Subscription _rover_position_setpoint_sub{ORB_ID(rover_position_setpoint)}; - vehicle_control_mode_s _vehicle_control_mode{}; - offboard_control_mode_s _offboard_control_mode{}; rover_position_setpoint_s _rover_position_setpoint{}; - // uORB publications uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; uORB::Publication _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)}; - uORB::Publication _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)}; // Variables - hrt_abstime _timestamp{0}; - Quatf _vehicle_attitude_quaternion{}; Vector2f _curr_pos_ned{}; Vector2f _start_ned{}; - Vector2f _pos_ctl_course_direction{}; - Vector2f _pos_ctl_start_position_ned{}; - float _vehicle_speed{0.f}; // [m/s] Positiv: Forwards, Negativ: Backwards float _vehicle_yaw{0.f}; - float _max_yaw_rate{0.f}; - float _dt{0.f}; - int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE}; - bool _prev_param_check_passed{true}; - - // Waypoint variables - Vector2f _curr_wp_ned{}; - Vector2f _prev_wp_ned{}; - Vector2f _next_wp_ned{}; - float _cruising_speed{0.f}; - float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad] - - // Class Instances - MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates DEFINE_PARAMETERS( - (ParamFloat) _param_rd_trans_drv_trn, - (ParamFloat) _param_rd_miss_spd_gain, - (ParamFloat) _param_ro_max_thr_speed, - (ParamFloat) _param_ro_yaw_stick_dz, (ParamFloat) _param_ro_decel_limit, (ParamFloat) _param_ro_jerk_limit, (ParamFloat) _param_ro_speed_limit, - (ParamFloat) _param_ro_speed_th, - (ParamFloat) _param_ro_yaw_p, (ParamFloat) _param_pp_lookahd_gain, (ParamFloat) _param_pp_lookahd_max, (ParamFloat) _param_pp_lookahd_min, - (ParamFloat) _param_ro_yaw_rate_limit, (ParamFloat) _param_nav_acc_rad ) }; diff --git a/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.cpp b/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.cpp index 8b8e7005a1..045d992157 100644 --- a/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.cpp +++ b/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.cpp @@ -37,8 +37,6 @@ using namespace time_literals; DifferentialRateControl::DifferentialRateControl(ModuleParams *parent) : ModuleParams(parent) { - _rover_rate_setpoint_pub.advertise(); - _rover_throttle_setpoint_pub.advertise(); _rover_steering_setpoint_pub.advertise(); _rover_rate_status_pub.advertise(); updateParams(); @@ -47,24 +45,21 @@ DifferentialRateControl::DifferentialRateControl(ModuleParams *parent) : ModuleP void DifferentialRateControl::updateParams() { ModuleParams::updateParams(); - _max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F; - _max_yaw_accel = _param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F; - _max_yaw_decel = _param_ro_yaw_decel_limit.get() * M_DEG_TO_RAD_F; + + // Set up PID controller _pid_yaw_rate.setGains(_param_ro_yaw_rate_p.get(), _param_ro_yaw_rate_i.get(), 0.f); _pid_yaw_rate.setIntegralLimit(1.f); _pid_yaw_rate.setOutputLimit(1.f); - _adjusted_yaw_rate_setpoint.setSlewRate(_max_yaw_accel); + + // Set up slew rate + _adjusted_yaw_rate_setpoint.setSlewRate(_param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F); } void DifferentialRateControl::updateRateControl() { - const hrt_abstime timestamp_prev = _timestamp; + hrt_abstime timestamp_prev = _timestamp; _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); - } + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; if (_vehicle_angular_velocity_sub.updated()) { vehicle_angular_velocity_s vehicle_angular_velocity{}; @@ -73,16 +68,25 @@ void DifferentialRateControl::updateRateControl() vehicle_angular_velocity.xyz[2] : 0.f; } - if (_vehicle_control_mode.flag_control_rates_enabled && _vehicle_control_mode.flag_armed && runSanityChecks()) { - if (_vehicle_control_mode.flag_control_manual_enabled || _vehicle_control_mode.flag_control_offboard_enabled) { - generateRateAndThrottleSetpoint(); - } + if (_rover_rate_setpoint_sub.updated()) { + rover_rate_setpoint_s rover_rate_setpoint{}; + _rover_rate_setpoint_sub.copy(&rover_rate_setpoint); + _yaw_rate_setpoint = rover_rate_setpoint.yaw_rate_setpoint; + } - generateSteeringSetpoint(); + if (PX4_ISFINITE(_yaw_rate_setpoint)) { + const float yaw_rate_setpoint = fabsf(_yaw_rate_setpoint) > _param_ro_yaw_rate_th.get() * M_DEG_TO_RAD_F ? + _yaw_rate_setpoint : 0.f; + const float speed_diff_normalized = RoverControl::rateControl(_adjusted_yaw_rate_setpoint, _pid_yaw_rate, + yaw_rate_setpoint, _vehicle_yaw_rate, _param_rd_max_thr_yaw_r.get(), _param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F, + _param_ro_yaw_decel_limit.get() * M_DEG_TO_RAD_F, _param_rd_wheel_track.get(), dt); + rover_steering_setpoint_s rover_steering_setpoint{}; + rover_steering_setpoint.timestamp = _timestamp; + rover_steering_setpoint.normalized_speed_diff = speed_diff_normalized; + _rover_steering_setpoint_pub.publish(rover_steering_setpoint); - } else { // Reset controller and slew rate when rate control is not active + } else { _pid_yaw_rate.resetIntegral(); - _adjusted_yaw_rate_setpoint.setForcedValue(0.f); } // Publish rate controller status (logging only) @@ -95,96 +99,17 @@ void DifferentialRateControl::updateRateControl() } -void DifferentialRateControl::generateRateAndThrottleSetpoint() -{ - const bool acro_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled - && !_vehicle_control_mode.flag_control_position_enabled && !_vehicle_control_mode.flag_control_attitude_enabled; - - if (acro_mode_enabled && _manual_control_setpoint_sub.updated()) { // Acro Mode - manual_control_setpoint_s manual_control_setpoint{}; - - if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle; - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - rover_rate_setpoint_s rover_rate_setpoint{}; - rover_rate_setpoint.timestamp = _timestamp; - rover_rate_setpoint.yaw_rate_setpoint = math::interpolate (manual_control_setpoint.roll, -1.f, 1.f, - -_max_yaw_rate, _max_yaw_rate); - _rover_rate_setpoint_pub.publish(rover_rate_setpoint); - } - - } else if (_vehicle_control_mode.flag_control_offboard_enabled) { // Offboard rate control - trajectory_setpoint_s trajectory_setpoint{}; - _trajectory_setpoint_sub.copy(&trajectory_setpoint); - - if (_offboard_control_mode_sub.updated()) { - _offboard_control_mode_sub.copy(&_offboard_control_mode); - } - - const bool offboard_rate_control = _offboard_control_mode.body_rate && !_offboard_control_mode.position - && !_offboard_control_mode.velocity && !_offboard_control_mode.attitude; - - if (offboard_rate_control && PX4_ISFINITE(trajectory_setpoint.yawspeed)) { - rover_rate_setpoint_s rover_rate_setpoint{}; - rover_rate_setpoint.timestamp = _timestamp; - rover_rate_setpoint.yaw_rate_setpoint = trajectory_setpoint.yawspeed; - _rover_rate_setpoint_pub.publish(rover_rate_setpoint); - } - } -} - -void DifferentialRateControl::generateSteeringSetpoint() -{ - if (_rover_rate_setpoint_sub.updated()) { - _rover_rate_setpoint_sub.copy(&_rover_rate_setpoint); - - } - - float speed_diff_normalized{0.f}; - - if (PX4_ISFINITE(_rover_rate_setpoint.yaw_rate_setpoint) && PX4_ISFINITE(_vehicle_yaw_rate)) { - const float yaw_rate_setpoint = fabsf(_rover_rate_setpoint.yaw_rate_setpoint) > _param_ro_yaw_rate_th.get() * - M_DEG_TO_RAD_F ? - _rover_rate_setpoint.yaw_rate_setpoint : 0.f; - speed_diff_normalized = RoverControl::rateControl(_adjusted_yaw_rate_setpoint, _pid_yaw_rate, - yaw_rate_setpoint, _vehicle_yaw_rate, _param_rd_max_thr_yaw_r.get(), _max_yaw_accel, - _max_yaw_decel, _param_rd_wheel_track.get(), _dt); - } - - rover_steering_setpoint_s rover_steering_setpoint{}; - rover_steering_setpoint.timestamp = _timestamp; - rover_steering_setpoint.normalized_speed_diff = speed_diff_normalized; - _rover_steering_setpoint_pub.publish(rover_steering_setpoint); -} - bool DifferentialRateControl::runSanityChecks() { bool ret = true; - if (_param_ro_yaw_rate_limit.get() < FLT_EPSILON) { - ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("differential_rate_control_conf_invalid_yaw_rate_lim"), events::Log::Error, - "Invalid configuration of necessary parameter RO_YAW_RATE_LIM", _param_ro_yaw_rate_limit.get()); - } - - } - if ((_param_rd_wheel_track.get() < FLT_EPSILON || _param_rd_max_thr_yaw_r.get() < FLT_EPSILON) && _param_ro_yaw_rate_p.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("differential_rate_control_conf_invalid_rate_control"), events::Log::Error, - "Invalid configuration for rate control: Neither feed forward nor feedback is setup", _param_rd_wheel_track.get(), - _param_rd_max_thr_yaw_r.get(), _param_ro_yaw_rate_p.get()); - } + events::send(events::ID("differential_rate_control_conf_invalid_rate_control"), events::Log::Error, + "Invalid configuration for rate control: Neither feed forward nor feedback is setup", _param_rd_wheel_track.get(), + _param_rd_max_thr_yaw_r.get(), _param_ro_yaw_rate_p.get()); } - _prev_param_check_passed = ret; return ret; } diff --git a/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.hpp b/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.hpp index da9b682f15..a58908fc9e 100644 --- a/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.hpp +++ b/src/modules/rover_differential/DifferentialRateControl/DifferentialRateControl.hpp @@ -47,15 +47,9 @@ #include #include #include -#include -#include -#include -#include #include #include -#include -#include -#include +#include /** * @brief Class for differential rate control. @@ -71,10 +65,21 @@ public: ~DifferentialRateControl() = default; /** - * @brief Update rate controller. + * @brief Generate and publish roverSteeringSetpoint from roverRateSetpoint. */ void updateRateControl(); + /** + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. + */ + bool runSanityChecks(); + + /** + * @brief Reset rate controller. + */ + void reset() {_pid_yaw_rate.resetIntegral(); _yaw_rate_setpoint = NAN;}; + protected: /** * @brief Update the parameters of the module. @@ -83,48 +88,18 @@ protected: private: - /** - * @brief Generate and publish roverRateSetpoint and roverThrottleSetpoint from manualControlSetpoint (Acro Mode). - */ - void generateRateAndThrottleSetpoint(); - - /** - * @brief Generate and publish roverSteeringSetpoint from RoverRateSetpoint. - */ - void generateSteeringSetpoint(); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); - // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; uORB::Subscription _rover_rate_setpoint_sub{ORB_ID(rover_rate_setpoint)}; uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; - uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; - vehicle_control_mode_s _vehicle_control_mode{}; - offboard_control_mode_s _offboard_control_mode{}; - rover_rate_setpoint_s _rover_rate_setpoint{}; // uORB publications - uORB::Publication _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)}; - uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; uORB::Publication _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)}; uORB::Publication _rover_rate_status_pub{ORB_ID(rover_rate_status)}; // Variables - hrt_abstime _timestamp{0}; - float _max_yaw_rate{0.f}; - float _max_yaw_accel{0.f}; - float _max_yaw_decel{0.f}; float _vehicle_yaw_rate{0.f}; - float _dt{0.f}; // Time since last update [s]. - bool _prev_param_check_passed{true}; + float _yaw_rate_setpoint{NAN}; + hrt_abstime _timestamp{0}; // Controllers PID _pid_yaw_rate; @@ -133,7 +108,6 @@ private: DEFINE_PARAMETERS( (ParamFloat) _param_rd_wheel_track, (ParamFloat) _param_rd_max_thr_yaw_r, - (ParamFloat) _param_ro_yaw_rate_limit, (ParamFloat) _param_ro_yaw_rate_th, (ParamFloat) _param_ro_yaw_rate_p, (ParamFloat) _param_ro_yaw_rate_i, diff --git a/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp b/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp index 2f8e3c8885..83d9542865 100644 --- a/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp +++ b/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp @@ -39,7 +39,6 @@ DifferentialVelControl::DifferentialVelControl(ModuleParams *parent) : ModulePar { _rover_throttle_setpoint_pub.advertise(); _rover_attitude_setpoint_pub.advertise(); - _rover_velocity_setpoint_pub.advertise(); _rover_velocity_status_pub.advertise(); updateParams(); } @@ -47,12 +46,15 @@ DifferentialVelControl::DifferentialVelControl(ModuleParams *parent) : ModulePar void DifferentialVelControl::updateParams() { ModuleParams::updateParams(); + + // Set up PID controller _pid_speed.setGains(_param_ro_speed_p.get(), _param_ro_speed_i.get(), 0.f); _pid_speed.setIntegralLimit(1.f); _pid_speed.setOutputLimit(1.f); + // Set up slew rate if (_param_ro_accel_limit.get() > FLT_EPSILON) { - _speed_setpoint.setSlewRate(_param_ro_accel_limit.get()); + _adjusted_speed_setpoint.setSlewRate(_param_ro_accel_limit.get()); } } @@ -60,39 +62,45 @@ void DifferentialVelControl::updateVelControl() { const hrt_abstime timestamp_prev = _timestamp; _timestamp = hrt_absolute_time(); - _dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; updateSubscriptions(); - if ((_vehicle_control_mode.flag_control_velocity_enabled) && _vehicle_control_mode.flag_armed && runSanityChecks()) { - if (_vehicle_control_mode.flag_control_offboard_enabled) { // Offboard Velocity Control - generateVelocitySetpoint(); - } + // Attitude Setpoint + if (PX4_ISFINITE(_bearing_setpoint)) { + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = _timestamp; + rover_attitude_setpoint.yaw_setpoint = _bearing_setpoint; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + } - generateAttitudeAndThrottleSetpoint(); + // Throttle Setpoint + if (PX4_ISFINITE(_speed_setpoint)) { + const float speed_setpoint = calcSpeedSetpoint(); + rover_throttle_setpoint_s rover_throttle_setpoint{}; + rover_throttle_setpoint.timestamp = _timestamp; + rover_throttle_setpoint.throttle_body_x = RoverControl::speedControl(_adjusted_speed_setpoint, _pid_speed, + speed_setpoint, _vehicle_speed, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(), + _param_ro_max_thr_speed.get(), dt); + rover_throttle_setpoint.throttle_body_y = 0.f; + _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - } else { // Reset controller and slew rate when velocity control is not active - _pid_speed.resetIntegral(); - _speed_setpoint.setForcedValue(0.f); } // Publish velocity controller status (logging only) rover_velocity_status_s rover_velocity_status; rover_velocity_status.timestamp = _timestamp; rover_velocity_status.measured_speed_body_x = _vehicle_speed; - rover_velocity_status.adjusted_speed_body_x_setpoint = _speed_setpoint.getState(); + rover_velocity_status.adjusted_speed_body_x_setpoint = _adjusted_speed_setpoint.getState(); rover_velocity_status.pid_throttle_body_x_integral = _pid_speed.getIntegral(); rover_velocity_status.measured_speed_body_y = NAN; rover_velocity_status.adjusted_speed_body_y_setpoint = NAN; rover_velocity_status.pid_throttle_body_y_integral = NAN; _rover_velocity_status_pub.publish(rover_velocity_status); } + void DifferentialVelControl::updateSubscriptions() { - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); - } - if (_vehicle_attitude_sub.updated()) { vehicle_attitude_s vehicle_attitude{}; _vehicle_attitude_sub.copy(&vehicle_attitude); @@ -109,46 +117,18 @@ void DifferentialVelControl::updateSubscriptions() _vehicle_speed = velocity_2d.norm() > _param_ro_speed_th.get() ? sign(velocity_2d(0)) * velocity_2d.norm() : 0.f; } -} - -void DifferentialVelControl::generateVelocitySetpoint() -{ - trajectory_setpoint_s trajectory_setpoint{}; - _trajectory_setpoint_sub.copy(&trajectory_setpoint); - - if (_offboard_control_mode_sub.updated()) { - _offboard_control_mode_sub.copy(&_offboard_control_mode); - } - - const bool offboard_vel_control = _offboard_control_mode.velocity && !_offboard_control_mode.position; - - const Vector2f velocity_in_local_frame(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]); - - if (offboard_vel_control && velocity_in_local_frame.isAllFinite()) { - rover_velocity_setpoint_s rover_velocity_setpoint{}; - rover_velocity_setpoint.timestamp = _timestamp; - rover_velocity_setpoint.speed = velocity_in_local_frame.norm(); - rover_velocity_setpoint.bearing = atan2f(velocity_in_local_frame(1), velocity_in_local_frame(0)); - _rover_velocity_setpoint_pub.publish(rover_velocity_setpoint); - } -} - -void DifferentialVelControl::generateAttitudeAndThrottleSetpoint() -{ if (_rover_velocity_setpoint_sub.updated()) { - _rover_velocity_setpoint_sub.copy(&_rover_velocity_setpoint); + rover_velocity_setpoint_s rover_velocity_setpoint; + _rover_velocity_setpoint_sub.copy(&rover_velocity_setpoint); + _speed_setpoint = rover_velocity_setpoint.speed; + _bearing_setpoint = rover_velocity_setpoint.bearing; } - // Attitude Setpoint - if (PX4_ISFINITE(_rover_velocity_setpoint.bearing)) { - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = _rover_velocity_setpoint.bearing; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } +} - // Throttle Setpoint - const float heading_error = matrix::wrap_pi(_rover_velocity_setpoint.bearing - _vehicle_yaw); +float DifferentialVelControl::calcSpeedSetpoint() +{ + const float heading_error = matrix::wrap_pi(_bearing_setpoint - _vehicle_yaw); if (_current_state == DrivingState::DRIVING && fabsf(heading_error) > _param_rd_trans_drv_trn.get()) { _current_state = DrivingState::SPOT_TURNING; @@ -160,32 +140,27 @@ void DifferentialVelControl::generateAttitudeAndThrottleSetpoint() float speed_setpoint = 0.f; if (_current_state == DrivingState::DRIVING) { - speed_setpoint = math::constrain(_rover_velocity_setpoint.speed, -_param_ro_speed_limit.get(), + speed_setpoint = math::constrain(_speed_setpoint, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get()); const float speed_setpoint_normalized = math::interpolate(speed_setpoint, -_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get(), -1.f, 1.f); if (_rover_steering_setpoint_sub.updated()) { - _rover_steering_setpoint_sub.copy(&_rover_steering_setpoint); + rover_steering_setpoint_s rover_steering_setpoint{}; + _rover_steering_setpoint_sub.copy(&rover_steering_setpoint); + _normalized_speed_diff = rover_steering_setpoint.normalized_speed_diff; } if (fabsf(speed_setpoint_normalized) > 1.f - fabsf( - _rover_steering_setpoint.normalized_speed_diff)) { // Adjust speed setpoint if it is infeasible due to the desired speed difference of the left/right wheels - speed_setpoint = math::interpolate(sign(speed_setpoint_normalized) * (1.f - fabsf( - _rover_steering_setpoint.normalized_speed_diff)), -1.f, 1.f, + _normalized_speed_diff)) { // Adjust speed setpoint if it is infeasible due to the desired speed difference of the left/right wheels + speed_setpoint = math::interpolate(sign(speed_setpoint_normalized) * (1.f - fabsf(_normalized_speed_diff)), -1.f, + 1.f, - _param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get()); } } - rover_throttle_setpoint_s rover_throttle_setpoint{}; - rover_throttle_setpoint.timestamp = _timestamp; - rover_throttle_setpoint.throttle_body_x = RoverControl::speedControl(_speed_setpoint, _pid_speed, - speed_setpoint, _vehicle_speed, _param_ro_accel_limit.get(), _param_ro_decel_limit.get(), - _param_ro_max_thr_speed.get(), _dt); - rover_throttle_setpoint.throttle_body_y = 0.f; - _rover_throttle_setpoint_pub.publish(rover_throttle_setpoint); - + return speed_setpoint; } bool DifferentialVelControl::runSanityChecks() @@ -194,25 +169,16 @@ bool DifferentialVelControl::runSanityChecks() if (_param_ro_speed_limit.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("differential_posVel_control_conf_invalid_speed_lim"), events::Log::Error, - "Invalid configuration of necessary parameter RO_SPEED_LIM", _param_ro_speed_limit.get()); - } - + events::send(events::ID("differential_posVel_control_conf_invalid_speed_lim"), events::Log::Error, + "Invalid configuration of necessary parameter RO_SPEED_LIM", _param_ro_speed_limit.get()); } if (_param_ro_max_thr_speed.get() < FLT_EPSILON && _param_ro_speed_p.get() < FLT_EPSILON) { ret = false; - - if (_prev_param_check_passed) { - events::send(events::ID("differential_posVel_control_conf_invalid_speed_control"), events::Log::Error, - "Invalid configuration for speed control: Neither feed forward (RO_MAX_THR_SPEED) nor feedback (RO_SPEED_P) is setup", - _param_ro_max_thr_speed.get(), - _param_ro_speed_p.get()); - } + events::send(events::ID("differential_posVel_control_conf_invalid_speed_control"), events::Log::Error, + "Invalid configuration for speed control: Neither feed forward (RO_MAX_THR_SPEED) nor feedback (RO_SPEED_P) is setup", + _param_ro_max_thr_speed.get(), _param_ro_speed_p.get()); } - _prev_param_check_passed = ret; return ret; } diff --git a/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.hpp b/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.hpp index c962382653..6a7a3c9689 100644 --- a/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.hpp +++ b/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.hpp @@ -47,15 +47,12 @@ // uORB includes #include #include -#include #include #include #include #include -#include -#include +#include #include -#include #include using namespace matrix; @@ -82,10 +79,21 @@ public: ~DifferentialVelControl() = default; /** - * @brief Update velocity controller. + * @brief Generate and publish roverAttitudeSetpoint/RoverThrottleSetpoint from roverVelocitySetpoint. */ void updateVelControl(); + /** + * @brief Check if the necessary parameters are set. + * @return True if all checks pass. + */ + bool runSanityChecks(); + + /** + * @brief Reset velocity controller. + */ + void reset() {_pid_speed.resetIntegral(); _speed_setpoint = NAN; _bearing_setpoint = NAN; _adjusted_speed_setpoint.setForcedValue(0.f);}; + protected: /** * @brief Update the parameters of the module. @@ -99,54 +107,35 @@ private: void updateSubscriptions(); /** - * @brief Generate and publish roverVelocitySetpoint from velocity of trajectorySetpoint. + * @brief Calculate the speed setpoint based on the current state. + * @return Speed setpoint. */ - void generateVelocitySetpoint(); - - /** - * @brief Generate and publish roverAttitudeSetpoint and roverThrottleSetpoint - * from roverVelocitySetpoint. - */ - void generateAttitudeAndThrottleSetpoint(); - - /** - * @brief Check if the necessary parameters are set. - * @return True if all checks pass. - */ - bool runSanityChecks(); + float calcSpeedSetpoint(); // uORB subscriptions - uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _rover_velocity_setpoint_sub{ORB_ID(rover_velocity_setpoint)}; uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)}; - vehicle_control_mode_s _vehicle_control_mode{}; - offboard_control_mode_s _offboard_control_mode{}; - rover_steering_setpoint_s _rover_steering_setpoint{}; // uORB publications uORB::Publication _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)}; uORB::Publication _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)}; uORB::Publication _rover_velocity_status_pub{ORB_ID(rover_velocity_status)}; - uORB::Publication _rover_velocity_setpoint_pub{ORB_ID(rover_velocity_setpoint)}; - rover_velocity_setpoint_s _rover_velocity_setpoint{}; // Variables hrt_abstime _timestamp{0}; Quatf _vehicle_attitude_quaternion{}; float _vehicle_speed{0.f}; // [m/s] Positiv: Forwards, Negativ: Backwards float _vehicle_yaw{0.f}; - float _dt{0.f}; - bool _prev_param_check_passed{false}; + float _speed_setpoint{NAN}; + float _bearing_setpoint{NAN}; + float _normalized_speed_diff{NAN}; DrivingState _current_state{DrivingState::DRIVING}; - // Controllers PID _pid_speed; - SlewRate _speed_setpoint; + SlewRate _adjusted_speed_setpoint; DEFINE_PARAMETERS( (ParamFloat) _param_rd_trans_trn_drv, diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index 99dd28d55f..4ab2d47187 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -56,35 +56,132 @@ void RoverDifferential::updateParams() void RoverDifferential::Run() { if (_parameter_update_sub.updated()) { + parameter_update_s param_update{}; + _parameter_update_sub.copy(¶m_update); updateParams(); + runSanityChecks(); } - _differential_pos_control.updatePosControl(); - _differential_vel_control.updateVelControl(); - _differential_att_control.updateAttControl(); - _differential_rate_control.updateRateControl(); - if (_vehicle_control_mode_sub.updated()) { - _vehicle_control_mode_sub.copy(&_vehicle_control_mode); + vehicle_control_mode_s vehicle_control_mode{}; + _vehicle_control_mode_sub.copy(&vehicle_control_mode); + + // Run sanity checks if the control mode changes (Note: This has to be done this way, because the topic is periodically updated at 2 Hz) + if (_vehicle_control_mode.flag_control_manual_enabled != vehicle_control_mode.flag_control_manual_enabled || + _vehicle_control_mode.flag_control_auto_enabled != vehicle_control_mode.flag_control_auto_enabled || + _vehicle_control_mode.flag_control_offboard_enabled != vehicle_control_mode.flag_control_offboard_enabled || + _vehicle_control_mode.flag_control_position_enabled != vehicle_control_mode.flag_control_position_enabled || + _vehicle_control_mode.flag_control_velocity_enabled != vehicle_control_mode.flag_control_velocity_enabled || + _vehicle_control_mode.flag_control_attitude_enabled != vehicle_control_mode.flag_control_attitude_enabled || + _vehicle_control_mode.flag_control_rates_enabled != vehicle_control_mode.flag_control_rates_enabled || + _vehicle_control_mode.flag_control_allocation_enabled != vehicle_control_mode.flag_control_allocation_enabled) { + _vehicle_control_mode = vehicle_control_mode; + runSanityChecks(); + reset(); + + } else { + _vehicle_control_mode = vehicle_control_mode; + } + } - const bool full_manual_mode_enabled = _vehicle_control_mode.flag_control_manual_enabled - && !_vehicle_control_mode.flag_control_position_enabled && !_vehicle_control_mode.flag_control_attitude_enabled - && !_vehicle_control_mode.flag_control_rates_enabled; + if (_vehicle_control_mode.flag_armed && _sanity_checks_passed) { - if (full_manual_mode_enabled) { // Manual mode - _differential_act_control.manualManualMode(); - } + _was_armed = true; - if (_vehicle_control_mode.flag_armed) { - _differential_act_control.updateActControl(); + // Generate setpoints + if (_vehicle_control_mode.flag_control_manual_enabled) { + manualControl(); - } else { + } else if (_vehicle_control_mode.flag_control_auto_enabled) { + _auto_mode.autoControl(); + + } else if (_vehicle_control_mode.flag_control_offboard_enabled) { + _offboard_mode.offboardControl(); + } + + updateControllers(); + + } else if (_was_armed) { // Reset all controllers and stop the vehicle + reset(); _differential_act_control.stopVehicle(); + _was_armed = false; } } +void RoverDifferential::manualControl() +{ + if (_vehicle_control_mode.flag_control_position_enabled) { + _manual_mode.position(); + + } else if (_vehicle_control_mode.flag_control_attitude_enabled) { + _manual_mode.stab(); + + } else if (_vehicle_control_mode.flag_control_rates_enabled) { + _manual_mode.acro(); + + } else if (_vehicle_control_mode.flag_control_allocation_enabled) { + _manual_mode.manual(); + } +} + +void RoverDifferential::updateControllers() +{ + if (_vehicle_control_mode.flag_control_position_enabled) { + _differential_pos_control.updatePosControl(); + } + + if (_vehicle_control_mode.flag_control_velocity_enabled) { + _differential_vel_control.updateVelControl(); + } + + if (_vehicle_control_mode.flag_control_attitude_enabled) { + _differential_att_control.updateAttControl(); + } + + if (_vehicle_control_mode.flag_control_rates_enabled) { + _differential_rate_control.updateRateControl(); + } + + if (_vehicle_control_mode.flag_control_allocation_enabled) { + _differential_act_control.updateActControl(); + } +} + +void RoverDifferential::runSanityChecks() +{ + if (_vehicle_control_mode.flag_control_rates_enabled && !_differential_rate_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + if (_vehicle_control_mode.flag_control_attitude_enabled && !_differential_att_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + if (_vehicle_control_mode.flag_control_velocity_enabled && !_differential_vel_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + if (_vehicle_control_mode.flag_control_position_enabled && !_differential_pos_control.runSanityChecks()) { + _sanity_checks_passed = false; + return; + } + + _sanity_checks_passed = true; +} + +void RoverDifferential::reset() +{ + _differential_vel_control.reset(); + _differential_att_control.reset(); + _differential_rate_control.reset(); + _manual_mode.reset(); +} + int RoverDifferential::task_spawn(int argc, char *argv[]) { RoverDifferential *instance = new RoverDifferential(); diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index 73fb3e735d..39ac21d2a8 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -40,6 +40,9 @@ #include #include +// Library includes +#include + // uORB includes #include #include @@ -51,6 +54,9 @@ #include "DifferentialAttControl/DifferentialAttControl.hpp" #include "DifferentialVelControl/DifferentialVelControl.hpp" #include "DifferentialPosControl/DifferentialPosControl.hpp" +#include "DifferentialDriveModes/DifferentialAutoMode/DifferentialAutoMode.hpp" +#include "DifferentialDriveModes/DifferentialManualMode/DifferentialManualMode.hpp" +#include "DifferentialDriveModes/DifferentialOffboardMode/DifferentialOffboardMode.hpp" class RoverDifferential : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem @@ -82,15 +88,46 @@ protected: private: void Run() override; + /** + * @brief Handle manual control + */ + void manualControl(); + + /** + * @brief Update the controllers + */ + void updateControllers(); + + /** + * @brief Check proper parameter setup for the controllers + * + * Modifies: + * + * - _sanity_checks_passed: true if checks for all active controllers pass + */ + void runSanityChecks(); + + /** + * @brief Reset controllers and manual mode variables. + */ + void reset(); + // uORB subscriptions uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; vehicle_control_mode_s _vehicle_control_mode{}; // Class instances - DifferentialActControl _differential_act_control{this}; - DifferentialRateControl _differential_rate_control{this}; - DifferentialAttControl _differential_att_control{this}; - DifferentialVelControl _differential_vel_control{this}; - DifferentialPosControl _differential_pos_control{this}; + DifferentialActControl _differential_act_control{this}; + DifferentialRateControl _differential_rate_control{this}; + DifferentialAttControl _differential_att_control{this}; + DifferentialVelControl _differential_vel_control{this}; + DifferentialPosControl _differential_pos_control{this}; + DifferentialAutoMode _auto_mode{this}; + DifferentialManualMode _manual_mode{this}; + DifferentialOffboardMode _offboard_mode{this}; + + // Variables + bool _sanity_checks_passed{true}; // True if checks for all active controllers pass + bool _was_armed{false}; // True if the vehicle was armed before the last reset }; From 62c9bf8a47a2e4079146cafd298dfafcbfb9a5c2 Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Tue, 27 May 2025 17:27:37 +0200 Subject: [PATCH 066/130] [uavcan] Param for interface mask of ESC actuators --- src/drivers/uavcan/actuators/esc.cpp | 7 +++++++ src/drivers/uavcan/module.yaml | 25 +++++++++++++++++++++++++ 2 files changed, 32 insertions(+) diff --git a/src/drivers/uavcan/actuators/esc.cpp b/src/drivers/uavcan/actuators/esc.cpp index 12f5d8600b..de1f5ad2a9 100644 --- a/src/drivers/uavcan/actuators/esc.cpp +++ b/src/drivers/uavcan/actuators/esc.cpp @@ -39,6 +39,7 @@ #include "esc.hpp" #include +#include #include #define MOTOR_BIT(x) (1<<(x)) @@ -66,6 +67,12 @@ UavcanEscController::init() _esc_status_pub.advertise(); + int32_t iface_mask{0xFF}; + + if (param_get(param_find("UAVCAN_ESC_IFACE"), &iface_mask) == OK) { + _uavcan_pub_raw_cmd.getTransferSender().setIfaceMask(iface_mask); + } + return res; } diff --git a/src/drivers/uavcan/module.yaml b/src/drivers/uavcan/module.yaml index 9c2ba643dc..0579870297 100644 --- a/src/drivers/uavcan/module.yaml +++ b/src/drivers/uavcan/module.yaml @@ -1,4 +1,29 @@ module_name: UAVCAN +parameters: +- group: UAVCAN + definitions: + UAVCAN_ESC_IFACE: + description: + short: Which CAN interfaces to output ESC messages on. + long: | + Since ESC messages are high priority and sent at a high rate, it is + recommended to only enable the interfaces that are actually used. + Otherwise, the ESC messages will arbitrate lower priority messages and + starve other nodes on the bus. + type: bitmask + bit: + 0: CAN1 + 1: CAN2 + 2: CAN3 + 3: CAN4 + 4: CAN5 + 5: CAN6 + 6: CAN7 + 7: CAN8 + default: 255 + min: 1 + max: 255 + reboot_required: true actuator_output: show_subgroups_if: 'UAVCAN_ENABLE>=3' config_parameters: From 418b653160ed88995c49862f73b553e4124d05c3 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Wed, 28 May 2025 15:30:59 +0200 Subject: [PATCH 067/130] DOCS: add FwLateralLongitudinalSetpointType documentation in px4-ros2-interface-lib --- .../fw_lat_long_ros_interaction.svg | 4 + docs/en/ros2/px4_ros2_control_interface.md | 134 +++++++++++++++++- 2 files changed, 137 insertions(+), 1 deletion(-) create mode 100644 docs/assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg diff --git a/docs/assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg b/docs/assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg new file mode 100644 index 0000000000..3e9a8df721 --- /dev/null +++ b/docs/assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg @@ -0,0 +1,4 @@ + + + +
    External Flight Mode
    Simplified PX4 Fixed Wing 
    Lateral/Longitudinal Controller


    Course Setpoint
    Airspeed Direction Computation
    Airspeed Direction Controller 
    Roll Angle Computation
    Airspeed Direction Setpoint
    Lateral Acceleration Setpoint
    +
    Diagram illustrates interaction between external inputs and PX4. Does not show all inputs and intermediate steps within the controller.
    Equivalent Airspeed Setpoint
    Altitude Setpoint
    Height Rate Setpoint
    Altitude Controller
    Airspeed Controller
    TECS
    pitch setpoint
    throttle setpoint
    \ No newline at end of file diff --git a/docs/en/ros2/px4_ros2_control_interface.md b/docs/en/ros2/px4_ros2_control_interface.md index 5259bde63d..343b42c78e 100644 --- a/docs/en/ros2/px4_ros2_control_interface.md +++ b/docs/en/ros2/px4_ros2_control_interface.md @@ -341,6 +341,7 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: - [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -355,7 +356,7 @@ You can add your own setpoint types by adding a class that inherits from `px4_ro This setpoint type is currently only supported for multicopters. ::: -Smoothly control position and (optionally) heading setpoints with the [px4_ros2::GotoSetpointType](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. The most trivial use is simply inputting a 3D position into the update method: @@ -400,6 +401,137 @@ _goto_setpoint->update( max_heading_rate_rad_s); ``` +#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) + + + +::: info +This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. +::: + +Use the [`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html) to directly control the lateral and longitudinal dynamics of a fixed-wing vehicle — that is, side-to-side motion (turning/banking) and forward/vertical motion (speeding up and climbing/descending), respectively. +This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../modules/modules_controller.md#fw-lat-lon-control), which decouples lateral and longitudinal inputs while ensuring that vehicle limits are respected. + +To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: + +1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. + If both are set to `NAN`, the vehicle will maintain its current altitude. +2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. + +For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). + +##### Basic Usage + +This type has a number of update methods, each allowing you to specify an increasing number of setpoints. + +The simplest method is `updateWithAltitude()`, which allows you to specify a `course` and `altitude` target setpoint: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, course); +``` + +PX4 uses the setpoints to compute the _roll angle_, _pitch angle_ and _throttle_ setpoints that are sent to lower level controllers. +Note that the commanded flight is expected to be relatively gentle/unaggressive when using this method. +This is done as follows: + +- Lateral control output: + + course setpoint (set by user) → airspeed direction (heading) setpoint → lateral acceleration setpoint → roll angle setpoint. + +- Longitudinal control output: + + altitude setpoint (set by user) → height rate setpoint → pitch angle setpoint and throttle settings. + +The `updateWithHeightRate()` method allows you to set a target `course` and `height_rate` (this is useful if the speed of ascent or descent matters, or needs to be dynamically controlled): + +```cpp +const float height_rate = 2.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithHeightRate(height_rate, course); +``` + +The `updateWithAltitude()` and `updateWithHeightRate()` methods allow you to additionally control the equivalent airspeed or lateral acceleration by specifying them as the third and fourth arguments, respectively: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +const float equivalent_aspd = 15.F; // m/s +const float lateral_acceleration = 2.F; // FRD, used as feedforward + +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, + course, + equivalent_aspd, + lateral_acceleration); +``` + +The equivalent airspeed and lateral acceleration arguments are defined as `std::optional`, so you can omit any of them by passing `std::nullopt`. + +::: tip +If both lateral acceleration and course setpoints are provided, the lateral acceleration setpoint will be used as feedforward. +::: + +##### Full Control Using the Setpoint Struct + +For full flexibility, you can create and pass a [`FwLateralLongitudinalSetpoint`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwLateralLongitudinalSetpoint.html) struct. +Each field is templated with `std::optional`. + +::: tip +If both course and airspeed direction are set: airspeed direction takes precedence, course is not controlled. +Lateral acceleration is treated as feedforward if either course or airspeed direction are also finite. +If both altitude and height rate are set: height rate takes precedence, altitude is not controlled. +::: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withCourse(0.F); +// setpoint_s.withAirspeedDirection(0.2F); // uncontrolled +setpoint_s.withLateralAcceleration(2.F); // feedforward +//setpoint_s.withAltitude(500.F); // uncontrolled +setpoint_s.withHeightRate(2.F); +setpoint_s.withEquivalentAirspeed(15.F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s); +``` + +The diagram below illustrates the interaction between the `FwLateralLongitudinalSetpointType` and PX4 when all inputs are set. + +![FW ROS Interaction](../../assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg) + +##### Advanced Configuration (Optional) + +You can also pass a [`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) struct along with the setpoint to override default controller settings and constraints such as pitch limits, throttle limits, and target sink/climb rates. +This is intended for advanced users: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withAirspeedDirection(0.F); +setpoint_s.withLateralAcceleration(2.F); // feedforward +setpoint_s.withAltitude(500.F); +setpoint_s.withEquivalentAirspeed(15.F); + +px4_ros2::FwControlConfiguration config_s; + +config_s.withTargetClimbRate(3.F); +config_s.withMaxAcceleration(5.F); +config_s.withThrottleLimits(0.4F, 0.6F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); +``` + +All configuration fields are defined as `std::optional`. +Unset values will default to the PX4 configuration. +See [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) and [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md) for more information on configuration options. + +:::info +For safety, PX4 automatically limits configuration values to stay within the vehicle’s constraints. +For example, throttle overrides are clamped to remain between [`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) +and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). +::: + #### Direct Actuator Control Setpoint (DirectActuatorsSetpointType) Actuators can be directly controlled using the [px4_ros2::DirectActuatorsSetpointType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) setpoint type. From 255216e4711ca297d933fd4c96bf4252b29d9f91 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Wed, 28 May 2025 15:31:25 +0200 Subject: [PATCH 068/130] DOCS: VTOL API documentation in px4-ros2-interface-lib --- docs/en/ros2/px4_ros2_control_interface.md | 46 +++++++++++++++++++++- 1 file changed, 45 insertions(+), 1 deletion(-) diff --git a/docs/en/ros2/px4_ros2_control_interface.md b/docs/en/ros2/px4_ros2_control_interface.md index 343b42c78e..a14a64c0a7 100644 --- a/docs/en/ros2/px4_ros2_control_interface.md +++ b/docs/en/ros2/px4_ros2_control_interface.md @@ -543,11 +543,55 @@ For example to control a quadrotor, you need to set the first 4 motors according If you want to control an actuator that does not control the vehicle's motion, but for example a payload servo, see [below](#controlling-an-independent-actuator-servo). ::: +### Controlling a VTOL + + + +To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: + +- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). + +As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. + +If you would like to command a VTOL transition in your external mode, you need to use the [VTOL API](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1VTOL.html). The VTOL API provides the functionality to command a transition and query the current state of the vehicle. + +Use this API with caution! +Commanding transitions externally makes the user partially responsible for ensuring smooth and safe behavior, unlike onboard transitions (e.g. via RC switch) where PX4 handles the full process: + +1. Ensure that both the `TrajectorySetpointType` and the `FwLateralLongitudinalSetpointType` are available to your mode. +2. Create an instance of `px4_ros2::VTOL` in the constructor of your mode. +3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. +4. During transition, send the following combination of setpoints: + + ```cpp + // Assuming the instance of the px4_ros2::VTOL object is called vtol + + // Send TrajectorySetpointType as follows: + Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); + Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; + + _trajectory_setpoint->update(velocity_sp, acceleration_sp); + + // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired + + float course_sp = 0.F; // North + + _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) + ``` + + This will ensure that the transition is handled properly within PX4. + You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + +To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. + +See [this external flight mode implementation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol) for a practical example on how to use this API. + ### Controlling an Independent Actuator/Servo If you want to control an independent actuator (a servo), follow these steps: -1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink) +1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). 2. Create an instance of [px4_ros2::PeripheralActuatorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html) in the constructor of your mode. 3. Call the `set()` method to control the actuator(s). This can be done independently of any active setpoints. From 029e0a7740d33bcdd92cdaa9b63f7748f5046871 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Wed, 28 May 2025 15:31:37 +0200 Subject: [PATCH 069/130] DOCS: add OdometryAirspeed docs --- docs/en/ros2/px4_ros2_control_interface.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/en/ros2/px4_ros2_control_interface.md b/docs/en/ros2/px4_ros2_control_interface.md index a14a64c0a7..8979861a7d 100644 --- a/docs/en/ros2/px4_ros2_control_interface.md +++ b/docs/en/ros2/px4_ros2_control_interface.md @@ -603,6 +603,7 @@ You can access PX4 telemetry topics directly via the following classes: - [OdometryGlobalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryGlobalPosition.html): Global position - [OdometryLocalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryLocalPosition.html): Local position, velocity, acceleration, and heading - [OdometryAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAttitude.html): Vehicle attitude +- [OdometryAirspeed](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAirspeed.html): Airspeed For example, you can query the vehicle's current position estimate as follows: From e338d8713b7f8f77ed7d7afdcc66e0ad933dcaac Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Wed, 28 May 2025 15:03:33 -0800 Subject: [PATCH 070/130] docs: add gazebo plugins doc (#24904) * docs: add gazebo plugins doc * add to sidebar and summary * prettier and link to sources * review feedback * Minor subedit and crosslink * Update docs/en/sim_gazebo_gz/plugins.md --------- Co-authored-by: Hamish Willee --- docs/en/SUMMARY.md | 1 + docs/en/_sidebar.md | 1 + docs/en/sim_gazebo_gz/index.md | 5 ++ docs/en/sim_gazebo_gz/plugins.md | 91 ++++++++++++++++++++++++++++++++ 4 files changed, 98 insertions(+) create mode 100644 docs/en/sim_gazebo_gz/plugins.md diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index ca350f182a..7c40adb54a 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -456,6 +456,7 @@ - [Vehicles](sim_gazebo_gz/vehicles.md) - [Advanced Lift Drag Tool](sim_gazebo_gz/tools_avl_automation.md) - [Worlds](sim_gazebo_gz/worlds.md) + - [Plugins](sim_gazebo_gz/plugins.md) - [Gazebo Models Repository](sim_gazebo_gz/gazebo_models.md) - [Multi-Vehicle Sim](sim_gazebo_gz/multi_vehicle_simulation.md) - [Gazebo Classic Simulation](sim_gazebo_classic/index.md) diff --git a/docs/en/_sidebar.md b/docs/en/_sidebar.md index f1629f15d9..16955fac10 100644 --- a/docs/en/_sidebar.md +++ b/docs/en/_sidebar.md @@ -457,6 +457,7 @@ - [Vehicles](/sim_gazebo_gz/vehicles.md) - [Advanced Lift Drag Tool](/sim_gazebo_gz/tools_avl_automation.md) - [Worlds](/sim_gazebo_gz/worlds.md) + - [Plugins](/sim_gazebo_gz/plugins.md) - [Gazebo Models Repository](/sim_gazebo_gz/gazebo_models.md) - [Multi-Vehicle Sim](/sim_gazebo_gz/multi_vehicle_simulation.md) - [Gazebo Classic Simulation](/sim_gazebo_classic/index.md) diff --git a/docs/en/sim_gazebo_gz/index.md b/docs/en/sim_gazebo_gz/index.md index bac64b0c9d..f4df3ea569 100644 --- a/docs/en/sim_gazebo_gz/index.md +++ b/docs/en/sim_gazebo_gz/index.md @@ -392,6 +392,11 @@ As long as the world file and the model file are in the Gazebo search path (`GZ_ However, `make px4_sitl gz__` won't work with them. ::: +## Extending Gazebo with Plugins + +World, vehicle (model), and sensor behaviour can be customised using plugins. +For more information see [Gazebo Plugins](../sim_gazebo_gz/plugins.md). + ## Multi-Vehicle Simulation Multi-Vehicle simulation is supported on Linux hosts. diff --git a/docs/en/sim_gazebo_gz/plugins.md b/docs/en/sim_gazebo_gz/plugins.md new file mode 100644 index 0000000000..3e4ea51e1d --- /dev/null +++ b/docs/en/sim_gazebo_gz/plugins.md @@ -0,0 +1,91 @@ +# Gazebo Plugins + +Gazebo plugins extend the simulator with custom functionality not provided by default. They can be attached to different entity types and allow you to add new sensors, modify world physics, or interact with the simulation environment. + +## Plugin Types + +Plugins can be attached to these entity types: + +- **World** - Global simulation behavior +- **Model** - Specific model functionality +- **Sensor** - Custom sensor implementations +- **Actor** - Dynamic entity behavior + +## Supported Plugins + +PX4 currently supports these plugins: + +- [OpticalFlowSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/optical_flow): Provides optical flow sensor simulation using OpenCV-based flow calculation. +- [GstCameraSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/gstreamer): Streams camera feeds via UDP (RTP/H.264) or RTMP with optional NVIDIA CUDA hardware acceleration. +- [MovingPlatformController](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/moving_platform_controller): Controls moving platforms (ships, trucks, etc.) for takeoff and landing scenarios. + Includes configurable velocity, heading, and random fluctuations. + +## Plugin Registration + +Plugins must be registered in the [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) file to be available in your world: + +```xml + + + + + + + + + + +``` + +## Creating Custom Plugins + +When developing new plugins: + +1. **Follow the plugin architecture** - Implement desired interfaces. + + You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. + The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). + +2. **Register your plugin** - Add it to [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) for discovery. +3. **Use the custom namespace** - Follow the pattern `custom::YourPluginName`. + +### Example Plugin Structure + +```cpp +class YourCustomSystem : + public gz::sim::System, + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemPostUpdate +{ +public: + void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; + void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; +}; + +// Plugin registration +GZ_ADD_PLUGIN(YourCustomSystem, gz::sim::System, + YourCustomSystem::ISystemPreUpdate, + YourCustomSystem::ISystemPostUpdate) +GZ_ADD_PLUGIN_ALIAS(YourCustomSystem, "custom::YourCustomSystem") +``` + +## Enabling a Plugin + +For world plugins all you need to do is [register the plugin](#plugin-registration) (add it to the `server.config`). +It will then be available to all worlds and vehicles. + +The process for adding vehicle model/sensor plugins is not documented. +This can tracked through [PX4-Autopilot#2493](https://github.com/PX4/PX4-Autopilot/issues/24939). + +## Resources + +- **PX4 Plugins**: [Repository source code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins) +- **Official Gazebo Documentation**: [System Plugins Guide](https://gazebosim.org/api/sim/9/createsystemplugins.html) +- **Server Configuration**: [Configuration Reference](https://gazebosim.org/api/sim/9/server_config.html) +- **PX4 Gazebo-classic Plugins**: [PX4 Gazebo Classic Plugins](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/main/src) + +::: info +Plugins for modern Gazebo are still evolving. The plugin system differs from Gazebo Classic. +::: From a89ec34e95b80f1460575263178706e9a6eafef2 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 28 May 2025 11:23:17 +0200 Subject: [PATCH 071/130] tropic-community: Add DTCM to heap move vectors to ITCM --- .../tropic-community/nuttx-config/nsh/defconfig | 4 +++- .../nuttx-config/scripts/script.ld | 16 ++-------------- 2 files changed, 5 insertions(+), 15 deletions(-) diff --git a/boards/nxp/tropic-community/nuttx-config/nsh/defconfig b/boards/nxp/tropic-community/nuttx-config/nsh/defconfig index 15122b439d..c184a37415 100644 --- a/boards/nxp/tropic-community/nuttx-config/nsh/defconfig +++ b/boards/nxp/tropic-community/nuttx-config/nsh/defconfig @@ -30,7 +30,7 @@ CONFIG_ARM_MPU=y CONFIG_ARM_MPU_RESET=y CONFIG_BOARDCTL_RESET=y CONFIG_BOARD_ASSERT_RESET_VALUE=0 -CONFIG_BOARD_LOOPSPERMSEC=114325 +CONFIG_BOARD_LOOPSPERMSEC=115000 CONFIG_BOARD_RESET_ON_ASSERT=2 CONFIG_BUILTIN=y CONFIG_CDCACM=y @@ -73,6 +73,7 @@ CONFIG_HAVE_CXXINITIALIZE=y CONFIG_I2C=y CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=2048 +CONFIG_IMXRT_DTCM_HEAP=y CONFIG_IMXRT_EDMA=y CONFIG_IMXRT_EDMA_EDBG=y CONFIG_IMXRT_EDMA_ELINK=y @@ -140,6 +141,7 @@ CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y CONFIG_MMCSD_SDIO=y +CONFIG_MM_REGIONS=2 CONFIG_MTD=y CONFIG_MTD_BYTE_WRITE=y CONFIG_MTD_PARTITION=y diff --git a/boards/nxp/tropic-community/nuttx-config/scripts/script.ld b/boards/nxp/tropic-community/nuttx-config/scripts/script.ld index 01d2e8d951..9c25a7e1a2 100644 --- a/boards/nxp/tropic-community/nuttx-config/scripts/script.ld +++ b/boards/nxp/tropic-community/nuttx-config/scripts/script.ld @@ -1,5 +1,5 @@ /**************************************************************************** - * boards/arm/imxrt/teensy-4.x/scripts/flash.ld + * boards/nxp/tropic-community/nuttx-config/scripts/script.ld * * Licensed to the Apache Software Foundation (ASF) under one or more * contributor license agreements. See the NOTICE file distributed with @@ -67,6 +67,7 @@ SECTIONS _sitcmfuncs = ABSOLUTE(.); FILL(0xFF) . = 0x40 ; + *(.ram_vectors) INCLUDE "itcm_static_functions.ld" INCLUDE "itcm_functions_includes.ld" . = ALIGN(8); @@ -75,19 +76,6 @@ SECTIONS _fitcmfuncs = LOADADDR(.itcmfunc); - /* The RAM vector table (if present) should lie at the beginning of SRAM */ - - .ram_vectors (COPY) : { - *(.ram_vectors) - } > dtcm - - - /* Workaround for ethernet issue, by placing g_desc_pool into DTCM, - which effectively puts it into a no-cache region */ - .dtcm : { - *(.bss.g_desc_pool) - } > dtcm - .text : { _stext = ABSOLUTE(.); From 64b9b52eb4e4c78ab4397f595aa6ef580ad46a21 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 28 May 2025 11:23:53 +0200 Subject: [PATCH 072/130] tropic-community: Update PX4 config --- boards/nxp/tropic-community/default.px4board | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/boards/nxp/tropic-community/default.px4board b/boards/nxp/tropic-community/default.px4board index 93e80bba11..f36d388a49 100644 --- a/boards/nxp/tropic-community/default.px4board +++ b/boards/nxp/tropic-community/default.px4board @@ -15,15 +15,19 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_BOSCH_BMI088=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y CONFIG_COMMON_INS=y CONFIG_COMMON_LIGHT=y CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y CONFIG_COMMON_MAGNETOMETER=y -CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_COMMON_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y @@ -47,8 +51,7 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_MODE_MANAGER=y -CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y From 1656278b5e03dd37bfd1c7b63b2e436f2fe078f0 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Wed, 28 May 2025 15:36:58 +0200 Subject: [PATCH 073/130] Update NuttX --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index eaf77e7e1a..db3dc7b9e6 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit eaf77e7e1a9ef418ce589269d12967348b04c20b +Subproject commit db3dc7b9e60b464c759d15f69fc3ee192aefa816 From b7f07a1ff7e2acc42e44547d69eecdb610ef8b6a Mon Sep 17 00:00:00 2001 From: lgf <1969354053@qq.com> Date: Thu, 29 May 2025 09:38:12 +0800 Subject: [PATCH 074/130] manifest: Add AmovLab ICF6 Signed-off-by: Ramon Roche --- platforms/common/pab_manifest.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/platforms/common/pab_manifest.c b/platforms/common/pab_manifest.c index 13911c1440..5e0cee9a30 100644 --- a/platforms/common/pab_manifest.c +++ b/platforms/common/pab_manifest.c @@ -404,7 +404,7 @@ static const px4_hw_mft_item_t base_configuration_18[] = { // BASE ID 0x100 Holybro Pixhawk Jetson Baseboard Alaised to ID 0 // BASE ID 0x150 ZeroOne Pixhawk Baseboard Alaised to ID 0 - +// BASE ID 0x200 AmovLab Pixhawk Baseboard Alaised to ID 0 static px4_hw_mft_list_entry_t mft_lists[] = { // ver_rev {HW_BASE_ID(0), base_configuration_0, arraySize(base_configuration_0)}, // std Base with PX4IO @@ -421,6 +421,7 @@ static px4_hw_mft_list_entry_t mft_lists[] = { {HW_BASE_ID(18), base_configuration_18, arraySize(base_configuration_18)}, // Auterion Skynode S ver 18 {HW_BASE_ID(0x100), base_configuration_0, arraySize(base_configuration_0)}, // Holybro Pixhawk Jetson Baseboard ver 0x100 Alaised to ID 0 {HW_BASE_ID(0x150), base_configuration_0, arraySize(base_configuration_0)}, // ZeroOne Pixhawk Baseboard ver 0x150 + {HW_BASE_ID(0x200), base_configuration_0, arraySize(base_configuration_0)}, // AmovLab Pixhawk Baseboard ver 0x150 }; /************************************************************************************ From d24893a847758d67deabb16aea91fa5ed94c3ce5 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Fri, 16 May 2025 11:49:00 -0700 Subject: [PATCH 075/130] tools: update docker_run.sh to use px4-dev updates to use the latest px4 development container Signed-off-by: Ramon Roche --- Tools/docker_run.sh | 24 ++---------------------- 1 file changed, 2 insertions(+), 22 deletions(-) diff --git a/Tools/docker_run.sh b/Tools/docker_run.sh index ad140f9f3c..121c659225 100755 --- a/Tools/docker_run.sh +++ b/Tools/docker_run.sh @@ -2,19 +2,7 @@ if [ -z ${PX4_DOCKER_REPO+x} ]; then echo "guessing PX4_DOCKER_REPO based on input"; - if [[ $@ =~ .*px4_fmu.* ]]; then - # nuttx-px4fmu-v{1,2,3,4,5} - PX4_DOCKER_REPO="px4io/px4-dev-nuttx-focal:2022-08-12" - elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*pilotpi.default ]] || [[ $@ =~ .*navigator.* ]]; then - # beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, scumaker_pilotpi_default, bluerobotics_navigator_default - PX4_DOCKER_REPO="px4io/px4-dev-armhf:2023-06-26" - elif [[ $@ =~ .*pilotpi.arm64 ]]; then - # scumaker_pilotpi_arm64 - PX4_DOCKER_REPO="px4io/px4-dev-aarch64:2022-08-12" - elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*bebop.* ]]; then - # posix_rpi_cross, posix_bebop_default - PX4_DOCKER_REPO="px4io/px4-dev-armhf:2023-06-26" - elif [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then + if [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then # clang tools PX4_DOCKER_REPO="px4io/px4-dev-clang:2021-02-04" elif [[ $@ =~ .*tests* ]]; then @@ -27,17 +15,9 @@ fi # otherwise default to nuttx if [ -z ${PX4_DOCKER_REPO+x} ]; then - PX4_DOCKER_REPO="px4io/px4-dev-nuttx-focal:2022-08-12" + PX4_DOCKER_REPO="px4io/px4-dev:v1.16.0-ondemand" fi -# docker hygiene - -#Delete all stopped containers (including data-only containers) -# docker container prune - -#Delete all 'untagged/dangling' () images -# docker image prune - echo "PX4_DOCKER_REPO: $PX4_DOCKER_REPO"; PWD=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) From 7f569542a2ef8dbc4549f12cf4f5aef6228c7ac0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bastian=20J=C3=A4ger?= <26868917+bastianhjaeger@users.noreply.github.com> Date: Sat, 31 May 2025 21:55:10 +0200 Subject: [PATCH 076/130] feat: allow PX4_UXRCE_DDS_NS override with empty sting (#24921) --- ROMFS/px4fmu_common/init.d-posix/rcS | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index 3619e17d03..e40647b9b4 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -295,10 +295,15 @@ then # for multi intances setup, add namespace prefix uxrce_dds_ns="-n px4_$px4_instance" fi -if [ -n "$PX4_UXRCE_DDS_NS" ] -then - # Override namespace if environment variable is defined - uxrce_dds_ns="-n $PX4_UXRCE_DDS_NS" +if [ "${PX4_UXRCE_DDS_NS+x}" ]; then + # Override, as variable is set (empty or not) + if [ -n "$PX4_UXRCE_DDS_NS" ]; then + # Override namespace if environment variable is non-empty + uxrce_dds_ns="-n $PX4_UXRCE_DDS_NS" + else + # Clear namespace if variable is empty + uxrce_dds_ns="" + fi fi if [ -n "$ROS_DOMAIN_ID" ] then From 793693732078d0cc77ceac23fa68f94958b7bdd1 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Mon, 2 Jun 2025 07:43:23 +1000 Subject: [PATCH 077/130] New Crowdin translations - ko (#24948) Co-authored-by: Crowdin Bot --- docs/ko/SUMMARY.md | 20 +- docs/ko/config/safety.md | 19 +- docs/ko/contribute/docs.md | 16 +- docs/ko/flight_modes_fw/land.md | 11 +- docs/ko/flight_modes_fw/takeoff.md | 42 +-- docs/ko/frames_plane/reptile_dragon_2.md | 2 +- docs/ko/middleware/uxrce_dds.md | 4 + docs/ko/modules/modules_controller.md | 32 ++- docs/ko/modules/modules_driver.md | 4 +- docs/ko/modules/modules_system.md | 1 + docs/ko/msg_docs/AirspeedValidated.md | 26 +- docs/ko/msg_docs/AirspeedValidatedV0.md | 25 ++ docs/ko/msg_docs/CellularStatus.md | 64 +++-- .../FixedWingLateralGuidanceStatus.md | 23 ++ docs/ko/msg_docs/FixedWingLateralSetpoint.md | 22 ++ docs/ko/msg_docs/FixedWingLateralStatus.md | 17 ++ .../msg_docs/FixedWingLongitudinalSetpoint.md | 26 ++ docs/ko/msg_docs/FixedWingRunwayControl.md | 19 ++ .../msg_docs/LateralControlConfiguration.md | 18 ++ .../LongitudinalControlConfiguration.md | 28 ++ docs/ko/msg_docs/PurePursuitStatus.md | 2 - docs/ko/msg_docs/RateCtrlStatus.md | 1 - docs/ko/msg_docs/RoverAttitudeSetpoint.md | 2 - docs/ko/msg_docs/RoverAttitudeStatus.md | 2 - docs/ko/msg_docs/RoverPositionSetpoint.md | 15 + docs/ko/msg_docs/RoverRateSetpoint.md | 2 - docs/ko/msg_docs/RoverRateStatus.md | 2 - docs/ko/msg_docs/RoverSteeringSetpoint.md | 5 +- docs/ko/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/ko/msg_docs/RoverVelocitySetpoint.md | 12 + docs/ko/msg_docs/RoverVelocityStatus.md | 10 +- docs/ko/msg_docs/TrajectorySetpoint6dof.md | 23 ++ docs/ko/msg_docs/VehicleAttitudeSetpoint.md | 6 +- docs/ko/msg_docs/VehicleAttitudeSetpointV0.md | 25 ++ docs/ko/msg_docs/VehicleCommand.md | 256 +++++++++--------- docs/ko/msg_docs/index.md | 38 ++- docs/ko/ros2/px4_ros2_control_interface.md | 181 ++++++++++++- docs/ko/sim_gazebo_gz/index.md | 5 + docs/ko/sim_gazebo_gz/plugins.md | 92 +++++++ docs/ko/telemetry/crsf_telemetry.md | 2 +- docs/ko/tutorials/linux_sbus.md | 10 +- 41 files changed, 864 insertions(+), 252 deletions(-) create mode 100644 docs/ko/msg_docs/AirspeedValidatedV0.md create mode 100644 docs/ko/msg_docs/FixedWingLateralGuidanceStatus.md create mode 100644 docs/ko/msg_docs/FixedWingLateralSetpoint.md create mode 100644 docs/ko/msg_docs/FixedWingLateralStatus.md create mode 100644 docs/ko/msg_docs/FixedWingLongitudinalSetpoint.md create mode 100644 docs/ko/msg_docs/FixedWingRunwayControl.md create mode 100644 docs/ko/msg_docs/LateralControlConfiguration.md create mode 100644 docs/ko/msg_docs/LongitudinalControlConfiguration.md create mode 100644 docs/ko/msg_docs/RoverPositionSetpoint.md create mode 100644 docs/ko/msg_docs/RoverVelocitySetpoint.md create mode 100644 docs/ko/msg_docs/TrajectorySetpoint6dof.md create mode 100644 docs/ko/msg_docs/VehicleAttitudeSetpointV0.md create mode 100644 docs/ko/sim_gazebo_gz/plugins.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index ac7dc4f91c..a41e987808 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -459,6 +459,7 @@ - [Vehicles](sim_gazebo_gz/vehicles.md) - [Advanced Lift Drag Tool](sim_gazebo_gz/tools_avl_automation.md) - [Worlds](sim_gazebo_gz/worlds.md) + - [Plugins](sim_gazebo_gz/plugins.md) - [Gazebo Models Repository](sim_gazebo_gz/gazebo_models.md) - [Multi-Vehicle Sim](sim_gazebo_gz/multi_vehicle_simulation.md) - [Gazebo Classic Simulation](sim_gazebo_classic/index.md) @@ -491,12 +492,17 @@ - [Versioned](msg_docs/versioned_messages.md) - [ActuatorMotors](msg_docs/ActuatorMotors.md) - [ActuatorServos](msg_docs/ActuatorServos.md) + - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [ArmingCheckReply](msg_docs/ArmingCheckReply.md) - [ArmingCheckRequest](msg_docs/ArmingCheckRequest.md) - [BatteryStatus](msg_docs/BatteryStatus.md) - [ConfigOverrides](msg_docs/ConfigOverrides.md) + - [FixedWingLateralSetpoint](msg_docs/FixedWingLateralSetpoint.md) + - [FixedWingLongitudinalSetpoint](msg_docs/FixedWingLongitudinalSetpoint.md) - [GotoSetpoint](msg_docs/GotoSetpoint.md) - [HomePosition](msg_docs/HomePosition.md) + - [LateralControlConfiguration](msg_docs/LateralControlConfiguration.md) + - [LongitudinalControlConfiguration](msg_docs/LongitudinalControlConfiguration.md) - [ManualControlSetpoint](msg_docs/ManualControlSetpoint.md) - [ModeCompleted](msg_docs/ModeCompleted.md) - [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md) @@ -525,10 +531,8 @@ - [ActuatorTest](msg_docs/ActuatorTest.md) - [AdcReport](msg_docs/AdcReport.md) - [Airspeed](msg_docs/Airspeed.md) - - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [AirspeedWind](msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](msg_docs/AutotuneAttitudeControlStatus.md) - - [Buffer128](msg_docs/Buffer128.md) - [ButtonEvent](msg_docs/ButtonEvent.md) - [CameraCapture](msg_docs/CameraCapture.md) - [CameraStatus](msg_docs/CameraStatus.md) @@ -567,6 +571,9 @@ - [FailsafeFlags](msg_docs/FailsafeFlags.md) - [FailureDetectorStatus](msg_docs/FailureDetectorStatus.md) - [FigureEightStatus](msg_docs/FigureEightStatus.md) + - [FixedWingLateralGuidanceStatus](msg_docs/FixedWingLateralGuidanceStatus.md) + - [FixedWingLateralStatus](msg_docs/FixedWingLateralStatus.md) + - [FixedWingRunwayControl](msg_docs/FixedWingRunwayControl.md) - [FlightPhaseEstimation](msg_docs/FlightPhaseEstimation.md) - [FollowTarget](msg_docs/FollowTarget.md) - [FollowTargetEstimator](msg_docs/FollowTargetEstimator.md) @@ -619,7 +626,6 @@ - [NavigatorMissionItem](msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](msg_docs/NavigatorStatus.md) - [NormalizedUnsignedSetpoint](msg_docs/NormalizedUnsignedSetpoint.md) - - [NpfgStatus](msg_docs/NpfgStatus.md) - [ObstacleDistance](msg_docs/ObstacleDistance.md) - [OffboardControlMode](msg_docs/OffboardControlMode.md) - [OnboardComputerStatus](msg_docs/OnboardComputerStatus.md) @@ -655,13 +661,12 @@ - [RcParameterMap](msg_docs/RcParameterMap.md) - [RoverAttitudeSetpoint](msg_docs/RoverAttitudeSetpoint.md) - [RoverAttitudeStatus](msg_docs/RoverAttitudeStatus.md) - - [RoverMecanumGuidanceStatus](msg_docs/RoverMecanumGuidanceStatus.md) - - [RoverMecanumSetpoint](msg_docs/RoverMecanumSetpoint.md) - - [RoverMecanumStatus](msg_docs/RoverMecanumStatus.md) + - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) + - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) - [RoverVelocityStatus](msg_docs/RoverVelocityStatus.md) - [Rpm](msg_docs/Rpm.md) - [RtlStatus](msg_docs/RtlStatus.md) @@ -693,6 +698,7 @@ - [TelemetryStatus](msg_docs/TelemetryStatus.md) - [TiltrotorExtraControls](msg_docs/TiltrotorExtraControls.md) - [TimesyncStatus](msg_docs/TimesyncStatus.md) + - [TrajectorySetpoint6dof](msg_docs/TrajectorySetpoint6dof.md) - [TransponderReport](msg_docs/TransponderReport.md) - [TuneControl](msg_docs/TuneControl.md) - [UavcanParameterRequest](msg_docs/UavcanParameterRequest.md) @@ -716,6 +722,8 @@ - [WheelEncoders](msg_docs/WheelEncoders.md) - [Wind](msg_docs/Wind.md) - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) + - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) + - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](middleware/mavlink.md) - [Adding Messages](mavlink/adding_messages.md) diff --git a/docs/ko/config/safety.md b/docs/ko/config/safety.md index 8b5f473854..facf431d8d 100644 --- a/docs/ko/config/safety.md +++ b/docs/ko/config/safety.md @@ -187,7 +187,24 @@ Due to the inherent danger of this, this function is disabled using [CBRK_FLIGHT ## Position (GNSS) Loss Failsafe -The _Position Loss Failsafe_ is triggered if the quality of the PX4 global position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The _Position Loss Failsafe_ is triggered if the quality of the PX4 position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The sections below cover first the trigger and then the failsafe action taken by the controller. + +### Position Loss Failsafe Trigger + +There are basically two mechanisms in PX4 to trigger position failsafes: + +- A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. +- The estimated horizontal position accuracy exceeds a certain threshold. This check is only done on hovering systems (rotary wing vehicles or VTOLs in hover phase). + +The relevant parameters shown below. + +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [EKF2_NOAID_TOUT](../advanced_config/parameter_reference.md#EKF2_NOAID_TOUT) | Maximum inertial dead-reckoning time, so the time after the last data sample was received of any sensor that constrains the velocity drift [microseconds]. | +| [COM_POS_FS_EPH](../advanced_config/parameter_reference.md#COM_POS_FS_EPH) | Horizontal position error threshold for hovering vehicles (Multicopters and VTOLs in hover). Fixed-wing vehicles have this value set to infinity. | + +### Position Loss Failsafe Action The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): diff --git a/docs/ko/contribute/docs.md b/docs/ko/contribute/docs.md index c5da3044ef..ea06c97615 100644 --- a/docs/ko/contribute/docs.md +++ b/docs/ko/contribute/docs.md @@ -182,11 +182,19 @@ Within the repository you created above: 5. Open previewed pages in your local editor: First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. - For example, on Windows command line you can enable VSCode as your default editor by entering: + For example, you can enable VSCode as your default editor by entering: - ```sh - set EDITOR=code - ``` + - Windows: + + ```sh + set EDITOR=code + ``` + + - Linux: + + ```sh + export EDITOR=code + ``` The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). diff --git a/docs/ko/flight_modes_fw/land.md b/docs/ko/flight_modes_fw/land.md index 3a96fa27f5..4287ea3ac3 100644 --- a/docs/ko/flight_modes_fw/land.md +++ b/docs/ko/flight_modes_fw/land.md @@ -41,11 +41,12 @@ The vehicle will flare if configured to do so (see [Flaring](../flight_modes_fw/ Land mode behaviour can be configured using the parameters below. -| 매개변수 | 설명 | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------- | -| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | -| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | -| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | +| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | +| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. | ## See Also diff --git a/docs/ko/flight_modes_fw/takeoff.md b/docs/ko/flight_modes_fw/takeoff.md index a22a5df021..4de2c68554 100644 --- a/docs/ko/flight_modes_fw/takeoff.md +++ b/docs/ko/flight_modes_fw/takeoff.md @@ -43,13 +43,14 @@ Reaching the clearance altitude causes the vehicle to enter [Hold mode](../fligh Parameters that affect both catapult/hand-launch and runway takeoffs: -| 매개변수 | 설명 | -| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Minimum altitude setpoint above Home that the vehicle will climb to during takeoff. | -| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) | -| [FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | This is the minimum pitch angle setpoint during the climbout phase | -| [FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Maximum climb rate. | -| [FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Flaps setpoint during takeoff | +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Minimum altitude setpoint above Home that the vehicle will climb to during takeoff. | +| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) | +| [FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | This is the minimum pitch angle setpoint during the climbout phase | +| [FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Maximum climb rate. | +| [FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Flaps setpoint during takeoff | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_TKO_AIRSPD is below FW_AIRSPD_MIN. | :::info The vehicle always respects normal FW max/min throttle settings during takeoff ([FW_THR_MIN](../advanced_config/parameter_reference.md#FW_THR_MIN), [FW_THR_MAX](../advanced_config/parameter_reference.md#FW_THR_MAX)). @@ -101,26 +102,25 @@ The _runway takeoff mode_ has the following phases: :::info For a smooth takeoff, the runway wheel controller possibly needs to be tuned. -It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)) and an outer loop that calculates heading setpoints from course errors and can be tuned via [RWTO_NPFG_PERIOD](#RWTO_NPFG_PERIOD). +It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)). ::: ### Parameters (Runway Takeoff) Runway takeoff is affected by the following parameters: -| 매개변수 | 설명 | -| ----------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Enable runway takeoff | -| [FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Enable wheel controller | -| [RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Max throttle during runway takeoff | -| [RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Throttle ramp up time | -| [RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Airspeed threshold to start rotation (pitching up). If not configured by operator is set to 0.9\*FW_TKO_AIRSPD. | -| [RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation. | -| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Airspeed setpoint during the takeoff climbout phase (after rotation). If not configured by operator is set to FW_AIRSPD_MIN. | -| [RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Enable wheel controller nudging while on the runway | -| [FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | The wingspan of the vehicle. Used to prevent wingstrikes. | -| [FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | The height of the wings above ground (ground clearance). Used to prevent wingstrikes. | -| [RWTO_NPFG_PERIOD](../advanced_config/parameter_reference.md#RWTO_NPFG_PERIOD) | L1 period while steering on runway. Increase for less aggressive response to course errors. | +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Enable runway takeoff | +| [FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Enable wheel controller | +| [RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Max throttle during runway takeoff | +| [RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Throttle ramp up time | +| [RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Airspeed threshold to start rotation (pitching up). If not configured by operator is set to 0.9\*FW_TKO_AIRSPD. | +| [RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation. | +| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Airspeed setpoint during the takeoff climbout phase (after rotation). If not configured by operator is set to FW_AIRSPD_MIN. | +| [RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Enable wheel controller nudging while on the runway | +| [FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | The wingspan of the vehicle. Used to prevent wingstrikes. | +| [FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | The height of the wings above ground (ground clearance). Used to prevent wingstrikes. | ## See Also diff --git a/docs/ko/frames_plane/reptile_dragon_2.md b/docs/ko/frames_plane/reptile_dragon_2.md index ee850cee30..0434987406 100644 --- a/docs/ko/frames_plane/reptile_dragon_2.md +++ b/docs/ko/frames_plane/reptile_dragon_2.md @@ -325,7 +325,7 @@ Access to this cable can be accomplished by simply removing the rear hatch and u ## Firmware Build -You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. +You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver_radio_control.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. These require some custom configuration to enable. diff --git a/docs/ko/middleware/uxrce_dds.md b/docs/ko/middleware/uxrce_dds.md index 3450478fb3..26c237a92c 100644 --- a/docs/ko/middleware/uxrce_dds.md +++ b/docs/ko/middleware/uxrce_dds.md @@ -435,9 +435,11 @@ publications: - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry + rate_limit: 150. - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus + rate_limit: 50. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint @@ -472,6 +474,8 @@ Each (`topic`,`type`) pairs defines: - `/fmu/out/` for topics that are _published_ by PX4. - `/fmu/in/` for topics that are _subscribed_ by PX4. 4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition. +5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2. + If left unspecified, the maximum publication rate limit is set to 100 Hz. `subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively. Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers. diff --git a/docs/ko/modules/modules_controller.md b/docs/ko/modules/modules_controller.md index c759734d7b..7286d3506f 100644 --- a/docs/ko/modules/modules_controller.md +++ b/docs/ko/modules/modules_controller.md @@ -91,18 +91,18 @@ fw_att_control [arguments...] status print status info ``` -## fw_pos_control +## fw_lat_lon_control -Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_pos_control) +Source: [modules/fw_lateral_longitudinal_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_lateral_longitudinal_control) ### 설명 -fw_pos_control is the fixed-wing position controller. +fw_lat_lon_control computes attitude and throttle setpoints from lateral and longitudinal control setpoints. -### Usage {#fw_pos_control_usage} +### Usage {#fw_lat_lon_control_usage} ``` -fw_pos_control [arguments...] +fw_lat_lon_control [arguments...] Commands: start [vtol] VTOL mode @@ -112,6 +112,28 @@ fw_pos_control [arguments...] status print status info ``` +## fw_mode_manager + +Source: [modules/fw_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_mode_manager) + +### 설명 + +This implements the setpoint generation for all PX4-internal fixed-wing modes, height-rate control and higher. +It takes the current mode state of the vehicle as input and outputs setpoints consumed by the fixed-wing +lateral-longitudinal controller and and controllers below that (attitude, rate). + +### Usage {#fw_mode_manager_usage} + +``` +fw_mode_manager [arguments...] + Commands: + start + + stop + + status print status info +``` + ## fw_rate_control Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_rate_control) diff --git a/docs/ko/modules/modules_driver.md b/docs/ko/modules/modules_driver.md index a0209ba330..36e1e5f032 100644 --- a/docs/ko/modules/modules_driver.md +++ b/docs/ko/modules/modules_driver.md @@ -293,7 +293,9 @@ dshot [arguments...] start telemetry Enable Telemetry on a UART - UART device + -d UART device + values: + [-x] Swap RX/TX pins reverse Reverse motor direction [-m ] Motor index (1-based, default=all) diff --git a/docs/ko/modules/modules_system.md b/docs/ko/modules/modules_system.md index e621beca92..7b96ffa2f4 100644 --- a/docs/ko/modules/modules_system.md +++ b/docs/ko/modules/modules_system.md @@ -318,6 +318,7 @@ i2c_launcher [arguments...] Commands: start -b Bus number + -t battery index for calibration values (1 or 3) stop diff --git a/docs/ko/msg_docs/AirspeedValidated.md b/docs/ko/msg_docs/AirspeedValidated.md index eef1300688..9034960626 100644 --- a/docs/ko/msg_docs/AirspeedValidated.md +++ b/docs/ko/msg_docs/AirspeedValidated.md @@ -1,21 +1,27 @@ # AirspeedValidated (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AirspeedValidated.msg) +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +uint32 MESSAGE_VERSION = 1 + uint64 timestamp # time since system start (microseconds) -float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid -float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid +float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +int8 airspeed_source # Source of currently published airspeed values +int8 DISABLED = -1 +int8 GROUND_MINUS_WIND = 0 +int8 SENSOR_1 = 1 +int8 SENSOR_2 = 2 +int8 SENSOR_3 = 3 +int8 SYNTHETIC = 4 + +# debug states float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid - -bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. - -int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid - +float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] float32 throttle_filtered # filtered fixed-wing throttle [-] float32 pitch_filtered # filtered pitch [rad] diff --git a/docs/ko/msg_docs/AirspeedValidatedV0.md b/docs/ko/msg_docs/AirspeedValidatedV0.md new file mode 100644 index 0000000000..8bca98a224 --- /dev/null +++ b/docs/ko/msg_docs/AirspeedValidatedV0.md @@ -0,0 +1,25 @@ +# AirspeedValidatedV0 (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/AirspeedValidatedV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid +float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid + +float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid +float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid + +bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. + +int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid + +float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] +float32 throttle_filtered # filtered fixed-wing throttle [-] +float32 pitch_filtered # filtered pitch [rad] + +``` diff --git a/docs/ko/msg_docs/CellularStatus.md b/docs/ko/msg_docs/CellularStatus.md index 4984dc9a6b..466a1272fe 100644 --- a/docs/ko/msg_docs/CellularStatus.md +++ b/docs/ko/msg_docs/CellularStatus.md @@ -1,35 +1,49 @@ # CellularStatus (UORB message) +Cellular status + +This is currently used only for logging cell status from MAVLink. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CellularStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Cellular status +# +# This is currently used only for logging cell status from MAVLink. -uint8 CELLULAR_STATUS_FLAG_UNKNOWN=0 # State unknown or not reportable -uint8 CELLULAR_STATUS_FLAG_FAILED=1 # velocity setpoint -uint8 CELLULAR_STATUS_FLAG_INITIALIZING=2 # Modem is being initialized -uint8 CELLULAR_STATUS_FLAG_LOCKED=3 # Modem is locked -uint8 CELLULAR_STATUS_FLAG_DISABLED=4 # Modem is not enabled and is powered down -uint8 CELLULAR_STATUS_FLAG_DISABLING=5 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLING=6 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLED=7 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint8 CELLULAR_STATUS_FLAG_SEARCHING=8 # Modem is searching for a network provider to register -uint8 CELLULAR_STATUS_FLAG_REGISTERED=9 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint8 CELLULAR_STATUS_FLAG_DISCONNECTING=10 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint8 CELLULAR_STATUS_FLAG_CONNECTING=11 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint8 CELLULAR_STATUS_FLAG_CONNECTED=12 # One or more packet data bearers is active and connected +uint64 timestamp # [us] Time since system start. -uint8 CELLULAR_NETWORK_FAILED_REASON_NONE=0 # No error -uint8 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN=1 # Error state is unknown -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING=2 # SIM is required for the modem but missing -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3 # SIM is available, but not usable for connection +uint16 status # [@enum STATUS_FLAG] Status bitmap. +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable. +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable. +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized. +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked. +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down. +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state. +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state. +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections. +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register. +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use. +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated. +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered. +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected. -uint16 status # Status bitmap 1: Roaming is active -uint8 failure_reason #Failure reason when status in in CELLUAR_STATUS_FAILED -uint8 type # Cellular network radio type 0: none 1: gsm 2: cdma 3: wcdma 4: lte -uint8 quality # Cellular network RSSI/RSRP in dBm, absolute value -uint16 mcc # Mobile country code. If unknown, set to: UINT16_MAX -uint16 mnc # Mobile network code. If unknown, set to: UINT16_MAX -uint16 lac # Location area code. If unknown, set to: 0 +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason. +uint8 FAILURE_REASON_NONE = 0 # No error. +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown. +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing. +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection. + +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type. +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE + +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value. +uint16 mcc # [@invalid UINT16_MAX] Mobile country code. +uint16 mnc # [@invalid UINT16_MAX] Mobile network code. +uint16 lac # [@invalid 0] Location area code. ``` diff --git a/docs/ko/msg_docs/FixedWingLateralGuidanceStatus.md b/docs/ko/msg_docs/FixedWingLateralGuidanceStatus.md new file mode 100644 index 0000000000..02dc50b410 --- /dev/null +++ b/docs/ko/msg_docs/FixedWingLateralGuidanceStatus.md @@ -0,0 +1,23 @@ +# FixedWingLateralGuidanceStatus (UORB message) + +Fixed Wing Lateral Guidance Status message +Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralGuidanceStatus.msg) + +```c +# Fixed Wing Lateral Guidance Status message +# Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +uint64 timestamp # time since system start (microseconds) + +float32 course_setpoint # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. Set by guidance law +float32 lateral_acceleration_ff # [m/s^2] [FRD] lateral acceleration demand only for maintaining curvature +float32 bearing_feas # [@range 0,1] bearing feasibility +float32 bearing_feas_on_track # [@range 0,1] on-track bearing feasibility +float32 signed_track_error # [m] signed track error +float32 track_error_bound # [m] track error bound +float32 adapted_period # [s] adapted period (if auto-tuning enabled) +uint8 wind_est_valid # [boolean] true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) + +``` diff --git a/docs/ko/msg_docs/FixedWingLateralSetpoint.md b/docs/ko/msg_docs/FixedWingLateralSetpoint.md new file mode 100644 index 0000000000..153167bb62 --- /dev/null +++ b/docs/ko/msg_docs/FixedWingLateralSetpoint.md @@ -0,0 +1,22 @@ +# FixedWingLateralSetpoint (UORB message) + +Fixed Wing Lateral Setpoint message +Used by the fw_lateral_longitudinal_control module +At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLateralSetpoint.msg) + +```c +# Fixed Wing Lateral Setpoint message +# Used by the fw_lateral_longitudinal_control module +# At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. +float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. +float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. + +``` diff --git a/docs/ko/msg_docs/FixedWingLateralStatus.md b/docs/ko/msg_docs/FixedWingLateralStatus.md new file mode 100644 index 0000000000..9214d1e9e0 --- /dev/null +++ b/docs/ko/msg_docs/FixedWingLateralStatus.md @@ -0,0 +1,17 @@ +# FixedWingLateralStatus (UORB message) + +Fixed Wing Lateral Status message +Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralStatus.msg) + +```c +# Fixed Wing Lateral Status message +# Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_acceleration_setpoint # [m/s^2] [FRD] resultant lateral acceleration setpoint +float32 can_run_factor # [norm] [@range 0, 1] estimate of certainty of the correct functionality of the npfg roll setpoint + +``` diff --git a/docs/ko/msg_docs/FixedWingLongitudinalSetpoint.md b/docs/ko/msg_docs/FixedWingLongitudinalSetpoint.md new file mode 100644 index 0000000000..6b8fb29e5b --- /dev/null +++ b/docs/ko/msg_docs/FixedWingLongitudinalSetpoint.md @@ -0,0 +1,26 @@ +# FixedWingLongitudinalSetpoint (UORB message) + +Fixed Wing Longitudinal Setpoint message +Used by the fw_lateral_longitudinal_control module +If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +If both altitude and height_rate are NAN, the controller maintains the current altitude. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLongitudinalSetpoint.msg) + +```c +# Fixed Wing Longitudinal Setpoint message +# Used by the fw_lateral_longitudinal_control module +# If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +# If both altitude and height_rate are NAN, the controller maintains the current altitude. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite +float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not controlled directly +float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used +float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller +float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller + +``` diff --git a/docs/ko/msg_docs/FixedWingRunwayControl.md b/docs/ko/msg_docs/FixedWingRunwayControl.md new file mode 100644 index 0000000000..9e9f5ff428 --- /dev/null +++ b/docs/ko/msg_docs/FixedWingRunwayControl.md @@ -0,0 +1,19 @@ +# FixedWingRunwayControl (UORB message) + +Auxiliary control fields for fixed-wing runway takeoff/landing + +Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingRunwayControl.msg) + +```c +# Auxiliary control fields for fixed-wing runway takeoff/landing + +# Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +uint64 timestamp # [us] time since system start + +bool wheel_steering_enabled # Flag that enables the wheel steering. +float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. + +``` diff --git a/docs/ko/msg_docs/LateralControlConfiguration.md b/docs/ko/msg_docs/LateralControlConfiguration.md new file mode 100644 index 0000000000..b0a03a6378 --- /dev/null +++ b/docs/ko/msg_docs/LateralControlConfiguration.md @@ -0,0 +1,18 @@ +# LateralControlConfiguration (UORB message) + +Fixed Wing Lateral Control Configuration message +Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LateralControlConfiguration.msg) + +```c +# Fixed Wing Lateral Control Configuration message +# Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY + +``` diff --git a/docs/ko/msg_docs/LongitudinalControlConfiguration.md b/docs/ko/msg_docs/LongitudinalControlConfiguration.md new file mode 100644 index 0000000000..901d5c23bc --- /dev/null +++ b/docs/ko/msg_docs/LongitudinalControlConfiguration.md @@ -0,0 +1,28 @@ +# LongitudinalControlConfiguration (UORB message) + +Fixed Wing Longitudinal Control Configuration message +Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +and configure the resultant setpoints. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LongitudinalControlConfiguration.msg) + +```c +# Fixed Wing Longitudinal Control Configuration message +# Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +# and configure the resultant setpoints. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 pitch_min # [rad][@range -pi, pi] defaults to FW_P_LIM_MIN if NAN. +float32 pitch_max # [rad][@range -pi, pi] defaults to FW_P_LIM_MAX if NAN. +float32 throttle_min # [norm] [@range 0,1] deaults to FW_THR_MIN if NAN. +float32 throttle_max # [norm] [@range 0,1] defaults to FW_THR_MAX if NAN. +float32 climb_rate_target # [m/s] target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only +bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking +bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller + +``` diff --git a/docs/ko/msg_docs/PurePursuitStatus.md b/docs/ko/msg_docs/PurePursuitStatus.md index 76ae5524f0..1685af32d1 100644 --- a/docs/ko/msg_docs/PurePursuitStatus.md +++ b/docs/ko/msg_docs/PurePursuitStatus.md @@ -11,6 +11,4 @@ float32 crosstrack_error # [m] Shortest distance from the vehicle to the pat float32 distance_to_waypoint # [m] Distance from the vehicle to the current waypoint float32 bearing_to_waypoint # [rad] Bearing towards current waypoint -# TOPICS pure_pursuit_status - ``` diff --git a/docs/ko/msg_docs/RateCtrlStatus.md b/docs/ko/msg_docs/RateCtrlStatus.md index c6a4323ae9..90eaa1208f 100644 --- a/docs/ko/msg_docs/RateCtrlStatus.md +++ b/docs/ko/msg_docs/RateCtrlStatus.md @@ -9,6 +9,5 @@ uint64 timestamp # time since system start (microseconds) float32 rollspeed_integ float32 pitchspeed_integ float32 yawspeed_integ -float32 wheel_rate_integ # FW only and optional ``` diff --git a/docs/ko/msg_docs/RoverAttitudeSetpoint.md b/docs/ko/msg_docs/RoverAttitudeSetpoint.md index fc2bc4d639..778d4407a9 100644 --- a/docs/ko/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/ko/msg_docs/RoverAttitudeSetpoint.md @@ -7,6 +7,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_setpoint # [rad] Expressed in NED frame -# TOPICS rover_attitude_setpoint - ``` diff --git a/docs/ko/msg_docs/RoverAttitudeStatus.md b/docs/ko/msg_docs/RoverAttitudeStatus.md index 28d9ef6d96..24dc3cf12f 100644 --- a/docs/ko/msg_docs/RoverAttitudeStatus.md +++ b/docs/ko/msg_docs/RoverAttitudeStatus.md @@ -8,6 +8,4 @@ uint64 timestamp # time since system start (microseconds) float32 measured_yaw # [rad/s] Measured yaw rate float32 adjusted_yaw_setpoint # [rad/s] Yaw setpoint that is being tracked (Applied slew rates) -# TOPICS rover_attitude_status - ``` diff --git a/docs/ko/msg_docs/RoverPositionSetpoint.md b/docs/ko/msg_docs/RoverPositionSetpoint.md new file mode 100644 index 0000000000..8450bf8486 --- /dev/null +++ b/docs/ko/msg_docs/RoverPositionSetpoint.md @@ -0,0 +1,15 @@ +# RoverPositionSetpoint (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32[2] position_ned # 2-dimensional position setpoint in NED frame [m] +float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position) +float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed) +float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero) + +float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw) + +``` diff --git a/docs/ko/msg_docs/RoverRateSetpoint.md b/docs/ko/msg_docs/RoverRateSetpoint.md index 71755a38f3..12fe8cb88c 100644 --- a/docs/ko/msg_docs/RoverRateSetpoint.md +++ b/docs/ko/msg_docs/RoverRateSetpoint.md @@ -7,6 +7,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_rate_setpoint # [rad/s] Expressed in NED frame -# TOPICS rover_rate_setpoint - ``` diff --git a/docs/ko/msg_docs/RoverRateStatus.md b/docs/ko/msg_docs/RoverRateStatus.md index 1f54694ee0..a3aa1d1164 100644 --- a/docs/ko/msg_docs/RoverRateStatus.md +++ b/docs/ko/msg_docs/RoverRateStatus.md @@ -9,6 +9,4 @@ float32 measured_yaw_rate # [rad/s] Measured yaw rate float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint that is being tracked (Applied slew rates) float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller -# TOPICS rover_rate_status - ``` diff --git a/docs/ko/msg_docs/RoverSteeringSetpoint.md b/docs/ko/msg_docs/RoverSteeringSetpoint.md index 1a6f3203dd..48353ea957 100644 --- a/docs/ko/msg_docs/RoverSteeringSetpoint.md +++ b/docs/ko/msg_docs/RoverSteeringSetpoint.md @@ -5,9 +5,8 @@ ```c uint64 timestamp # time since system start (microseconds) -float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Only for Ackermann-steered rovers) -float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Only for Differential/Mecanum rovers) +float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Ackermann only, Positiv: Steer right, Negativ: Steer left) -# TOPICS rover_steering_setpoint +float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Differential/Mecanum only, Positiv = Turn right, Negativ: Turn left) ``` diff --git a/docs/ko/msg_docs/RoverThrottleSetpoint.md b/docs/ko/msg_docs/RoverThrottleSetpoint.md index 9533126dd0..ccdf76902d 100644 --- a/docs/ko/msg_docs/RoverThrottleSetpoint.md +++ b/docs/ko/msg_docs/RoverThrottleSetpoint.md @@ -6,9 +6,7 @@ uint64 timestamp # time since system start (microseconds) -float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] -float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] - -# TOPICS rover_throttle_setpoint +float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] (Positiv = forwards, Negativ = backwards) +float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] (Mecanum only, Positiv = right, Negativ = left) ``` diff --git a/docs/ko/msg_docs/RoverVelocitySetpoint.md b/docs/ko/msg_docs/RoverVelocitySetpoint.md new file mode 100644 index 0000000000..2e2d322b47 --- /dev/null +++ b/docs/ko/msg_docs/RoverVelocitySetpoint.md @@ -0,0 +1,12 @@ +# RoverVelocitySetpoint (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocitySetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative) +float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction] +float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame + +``` diff --git a/docs/ko/msg_docs/RoverVelocityStatus.md b/docs/ko/msg_docs/RoverVelocityStatus.md index 02b2c3b527..c908ffac90 100644 --- a/docs/ko/msg_docs/RoverVelocityStatus.md +++ b/docs/ko/msg_docs/RoverVelocityStatus.md @@ -6,14 +6,10 @@ uint64 timestamp # time since system start (microseconds) float32 measured_speed_body_x # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards -float32 speed_body_x_setpoint # [m/s] Speed setpoint in body x direction. Positiv: forwards, Negativ: backwards float32 adjusted_speed_body_x_setpoint # [m/s] Post slew rate speed setpoint in body x direction. Positiv: forwards, Negativ: backwards -float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left -float32 speed_body_y_setpoint # [m/s] Speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) -float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) float32 pid_throttle_body_x_integral # Integral of the PID for the closed loop controller of the speed in body x direction -float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction - -# TOPICS rover_velocity_status +float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction (Mecanum only) ``` diff --git a/docs/ko/msg_docs/TrajectorySetpoint6dof.md b/docs/ko/msg_docs/TrajectorySetpoint6dof.md new file mode 100644 index 0000000000..f2629e19c4 --- /dev/null +++ b/docs/ko/msg_docs/TrajectorySetpoint6dof.md @@ -0,0 +1,23 @@ +# TrajectorySetpoint6dof (UORB message) + +Trajectory setpoint in NED frame +Input to position controller. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TrajectorySetpoint6dof.msg) + +```c +# Trajectory setpoint in NED frame +# Input to position controller. + +uint64 timestamp # time since system start (microseconds) + +# NED local world frame +float32[3] position # in meters +float32[3] velocity # in meters/second +float32[3] acceleration # in meters/second^2 +float32[3] jerk # in meters/second^3 (for logging only) + +float32[4] quaternion # unit quaternion +float32[3] angular_velocity # angular velocity in radians/second + +``` diff --git a/docs/ko/msg_docs/VehicleAttitudeSetpoint.md b/docs/ko/msg_docs/VehicleAttitudeSetpoint.md index e8dc7ebaf9..9cd9ba092b 100644 --- a/docs/ko/msg_docs/VehicleAttitudeSetpoint.md +++ b/docs/ko/msg_docs/VehicleAttitudeSetpoint.md @@ -3,7 +3,7 @@ [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) ```c -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # time since system start (microseconds) @@ -16,10 +16,6 @@ float32[4] q_d # Desired quaternion for quaternion control # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] -bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) - -bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) - # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint ``` diff --git a/docs/ko/msg_docs/VehicleAttitudeSetpointV0.md b/docs/ko/msg_docs/VehicleAttitudeSetpointV0.md new file mode 100644 index 0000000000..6eb03e797c --- /dev/null +++ b/docs/ko/msg_docs/VehicleAttitudeSetpointV0.md @@ -0,0 +1,25 @@ +# VehicleAttitudeSetpointV0 (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 yaw_sp_move_rate # rad/s (commanded by user) + +# For quaternion-based attitude control +float32[4] q_d # Desired quaternion for quaternion control + +# For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. +# For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. +float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] + +bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) + +bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) + +# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint + +``` diff --git a/docs/ko/msg_docs/VehicleCommand.md b/docs/ko/msg_docs/VehicleCommand.md index c2cc25f241..19557cf496 100644 --- a/docs/ko/msg_docs/VehicleCommand.md +++ b/docs/ko/msg_docs/VehicleCommand.md @@ -11,127 +11,127 @@ Follows the MAVLink COMMAND_INT / COMMAND_LONG definition uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start. -uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command -uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command -uint16 VEHICLE_CMD_CUSTOM_2 = 2 # test command -uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |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_PRECLAND = 23 # Attempt a precision landing -uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |Major Radius [m] |Minor Radius [m] |Velocity [m/s] |Orientation |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| -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_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_CONDITION_GATE = 4501 # Wait until passing a threshold |2D coord mode: 0: Orthogonal to planned route | Altitude mode: 0: Ignore altitude| Empty| Empty| Lat| Lon| Alt| -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 cycles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| 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_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value |Altitude| Frame of new altitude | Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1| Actuator 2| Actuator 3| Actuator 4| Actuator 5| Actuator 6| Index| -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 autonomous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |Ground speed [m/s] |Bitmask |Loiter radius [m] for planes |Yaw [deg] |Latitude |Longitude |Altitude | +uint16 VEHICLE_CMD_CUSTOM_0 = 0 # Test command. +uint16 VEHICLE_CMD_CUSTOM_1 = 1 # Test command. +uint16 VEHICLE_CMD_CUSTOM_2 = 2 # Test command. +uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |[s] (decimal) Hold time. (ignored by fixed wing, time to stay at MISSION for rotary wing)|[m] Acceptance radius (if the sphere with this radius is hit, the MISSION counts as reached)|0 to pass through the WP, if > 0 radius [m] to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.|Desired yaw angle at MISSION (rotary wing)|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time. |Unused|Unused|[m] Radius around MISSION. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns. |Turns|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for time. |[s] Seconds (decimal)|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand. |Unused (FW pitch from FW_TKO_PITCH_MIN)|Unused|Unused|[deg] [@range 0,360] Yaw angle in NED if yaw source available, ignored otherwise|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude AMSL| +uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing. +uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |[m] Radius|[m/s] Velocity|[@enum ORBIT_YAW_BEHAVIOUR] Yaw behaviour|Unused|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |[m] Major radius|[m] Minor radius|[m/s] Velocity|Orientation|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| +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|Unused|[deg] [@range 0, 360] Yaw angle at goal, in compass degrees|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|Unused|Unused|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. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min AMSL - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time. |[s] Delay (decimal, -1 to enable time-of-day fields)|[h] hour (24h format, UTC, -1 to ignore)|minute (24h format, UTC, -1 to ignore)|second (24h format, UTC)|Unused|Unused|Unused| +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.|Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |[s] Delay (decimal seconds)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached.|Descent / Ascend rate (m/s)|Unused|Unused|Unused|Unused|Unused|Finish Altitude| +uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance [m]|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |[deg] [@range 0,360] Target angle. 0 is north|[deg/s] Speed during yaw change|[@range -1,1] Direction: negative: counter clockwise, positive: clockwise |[ 1,0] Relative offset or absolute angle|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_GATE = 4501 # Wait until passing a threshold. |2D coord mode: 0: Orthogonal to planned route|Altitude mode: 0: Ignore altitude|Unused|Unused|Lat|Lon|Alt| +uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE|Unused|Unused|Unused|Unused|Unused|Unused| +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|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |[@enum SPEED_TYPE] Speed type (0=Airspeed, 1=Ground Speed)|Speed (m/s, -1 indicates no change)|[%] Throttle ( Percent, -1 indicates no change)|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|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|Unused|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cycles with a desired period. |Relay number|Cycle count|[s] Cycle time (decimal seconds)|Unused|Unused|Unused|Unused| +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|[us] PWM rate (1000 to 2000 typical)|Cycle count|[s] Cycle time|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately. |Flight termination activated if > 0.5|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value. |Altitude|Frame of new altitude|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1|Actuator 2|Actuator 3|Actuator 4|Actuator 5|Actuator 6|Index| +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. |Unused|Unused|Unused|Unused|Latitude|Longitude|Unused| +uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonomous landing. |[m] Altitude|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |[m/s] Ground speed|Bitmask|[m] Loiter radius for planes|[deg] Yaw|Latitude|Longitude|Altitude| uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193 -uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint| -uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| +uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Pitch offset from next waypoint|Roll offset from next waypoint|Yaw offset from next waypoint| +uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)|Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw|Transmission mode: 0: video stream, >0: single images every n seconds (decimal seconds)|Recording: 0: disabled, 1: enabled compressed, 2: enabled raw|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| uint16 VEHICLE_CMD_DO_DIGICAM_CONTROL=203 -uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # motor test command |Instance (1, ...)| throttle type| throttle| timeout [s]| Motor count | Test order| Empty| -uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # 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_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See mavlink spec MAV_CMD_PREFLIGHT_CALIBRATION -uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration -uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| -uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started -uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty| -uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode |MAV_STANDARD_MODE| -uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal +uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount. |[@enum MAV_MOUNT_MODE] Mount operation mode|Stabilize roll? (1 = yes, 0 = no)|Stabilize pitch? (1 = yes, 0 = no)|stabilize yaw? (1 = yes, 0 = no)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount. |[deg] Pitch or lat, depending on mount mode.|[deg] Roll or lon depending on mount mode|[deg]/[m] Yaw or alt depending on mount mode|Unused|Unused|Unused|[@enum MAV_MOUNT_MODE]| +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence. |enable? (0=disable, 1=enable)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute. |action [@enum PARACHUTE_ACTION] (0=disable, 1=enable, 2=release, for some systems see [@enum PARACHUTE_ACTION], not in general message set.)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # Motor test command. |Instance (@range 1, )|throttle type|throttle|timeout [s]|Motor count|Test order|Unused| +uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight. |inverted (0=normal, 1=inverted)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper. +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight. |[m] Camera trigger distance|Shutter integration time (ms)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)|q2 - quaternion param #2, x (0 in null-rotation)|q3 - quaternion param #3, y (0 in null-rotation)|q4 - quaternion param #4, z (0 in null-rotation)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min(AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See MAVLink spec MAV_CMD_PREFLIGHT_CALIBRATION. +uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# Param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration. +uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow|X axis offset (or generic dimension 1), in the sensor's raw units|Y axis offset (or generic dimension 2), in the sensor's raw units|Z axis offset (or generic dimension 3), in the sensor's raw units|Generic dimension 4, in the sensor's raw units|Generic dimension 5, in the sensor's raw units|Generic dimension 6, in the sensor's raw units| +uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started. +uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.|0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Camera minimum trigger interval|Number of positions|Roll|Pitch|Unused| +uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode. |MAV_STANDARD_MODE| +uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal. -uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| -uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command|value [-1,1]|timeout [s]|Empty|Empty|output function| -uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|configuration|Empty|Empty|Empty|output function| -uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm -uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. -uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes -uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| -uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message -uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| -uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.) -uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom +uint16 VEHICLE_CMD_MISSION_START = 300 # Start running a mission. |first_item: the first mission item to run|last_item: the last mission item to run (after this item is run, the mission ends)| +uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command. |[@range -1,1] value|[s] timeout|Unused|Unused|output function| +uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command. |configuration|Unused|Unused|Unused|output function| +uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component. |1 to arm, 0 to disarm. +uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. +uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes. +uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing. |0:Spektrum|0:Spektrum DSM2, 1:Spektrum DSMX| +uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message. +uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities|Reserved (all remaining params)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)| +uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). +uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control -uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. -uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system -uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. -uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. -uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data -uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data -uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link -uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition -uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization -uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan -uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment -uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. -uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. +uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. +uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. +uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. +uint16 VEHICLE_CMD_LOGGING_START = 2510 # Start streaming ULog data. +uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # Stop streaming ULog data. +uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # Control starting/stopping transmitting data over the high latency link. +uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition. +uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization. +uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan. +uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment. +uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. +uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. -uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # external reset of estimator global position when deadreckoning +uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # External reset of estimator global position when dead reckoning. uint16 VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE = 43004 -# PX4 vehicle commands (beyond 16 bit mavlink commands) -uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX) -uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude| -uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty| +# PX4 vehicle commands (beyond 16 bit MAVLink commands). +uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # Start of PX4 internal only vehicle commands (> UINT16_MAX). +uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Unused|Unused|Unused|Unused|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude (AMSL from GNSS, positive above ground)| +uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Unused|Unused|Unused|Unused|Unused|Unused| -uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization | -uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | -uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt | -uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # +uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization. +uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt. +uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # -uint8 VEHICLE_ROI_NONE = 0 # No region of interest | -uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | -uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | -uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | -uint8 VEHICLE_ROI_TARGET = 4 # Point toward target +uint8 VEHICLE_ROI_NONE = 0 # No region of interest. +uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION. +uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION. +uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location. +uint8 VEHICLE_ROI_TARGET = 4 # Point toward target. uint8 VEHICLE_ROI_ENUM_END = 5 uint8 PARACHUTE_ACTION_DISABLE = 0 @@ -163,13 +163,13 @@ uint8 FAILURE_TYPE_SLOW = 5 uint8 FAILURE_TYPE_DELAYED = 6 uint8 FAILURE_TYPE_INTERMITTENT = 7 -# used as param1 in DO_CHANGE_SPEED command +# Used as param1 in DO_CHANGE_SPEED command. uint8 SPEED_TYPE_AIRSPEED = 0 uint8 SPEED_TYPE_GROUNDSPEED = 1 uint8 SPEED_TYPE_CLIMB_SPEED = 2 uint8 SPEED_TYPE_DESCEND_SPEED = 3 -# used as param3 in CMD_DO_ORBIT +# Used as param3 in CMD_DO_ORBIT. uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0 uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 @@ -177,29 +177,29 @@ uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 -# used as param1 in ARM_DISARM command +# Used as param1 in ARM_DISARM command. int8 ARMING_ACTION_DISARM = 0 int8 ARMING_ACTION_ARM = 1 -# param2 in VEHICLE_CMD_DO_GRIPPER +# param2 in VEHICLE_CMD_DO_GRIPPER. uint8 GRIPPER_ACTION_RELEASE = 0 uint8 GRIPPER_ACTION_GRAB = 1 uint8 ORB_QUEUE_LENGTH = 8 -float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. -uint32 command # Command ID -uint8 target_system # System which should execute the command -uint8 target_component # Component which should execute the command, 0 for all components -uint8 source_system # System sending the command -uint16 source_component # Component / mode executor sending the command -uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. +uint32 command # Command ID. +uint8 target_system # System which should execute the command. +uint8 target_component # Component which should execute the command, 0 for all components. +uint8 source_system # System sending the command. +uint16 source_component # Component / mode executor sending the command. +uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command). bool from_external uint16 COMPONENT_MODE_EXECUTOR_START = 1000 diff --git a/docs/ko/msg_docs/index.md b/docs/ko/msg_docs/index.md index 3be60e4f9f..bcdfefd906 100644 --- a/docs/ko/msg_docs/index.md +++ b/docs/ko/msg_docs/index.md @@ -15,10 +15,18 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message +- [AirspeedValidated](AirspeedValidated.md) - [ArmingCheckReply](ArmingCheckReply.md) - [ArmingCheckRequest](ArmingCheckRequest.md) - [BatteryStatus](BatteryStatus.md) - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors +- [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message + Used by the fw_lateral_longitudinal_control module + At least one of course, airspeed_direction, or lateral_acceleration must be finite. +- [FixedWingLongitudinalSetpoint](FixedWingLongitudinalSetpoint.md) — Fixed Wing Longitudinal Setpoint message + Used by the fw_lateral_longitudinal_control module + If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. + If both altitude and height_rate are NAN, the controller maintains the current altitude. - [GotoSetpoint](GotoSetpoint.md) — Position and (optional) heading setpoints with corresponding speed constraints Setpoints are intended as inputs to position and heading smoothers, respectively Setpoints do not need to be kinematically consistent @@ -26,6 +34,11 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m Unset optional setpoints are not controlled Unset optional constraints default to vehicle specifications - [HomePosition](HomePosition.md) — GPS home position in WGS84 coordinates. +- [LateralControlConfiguration](LateralControlConfiguration.md) — Fixed Wing Lateral Control Configuration message + Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. +- [LongitudinalControlConfiguration](LongitudinalControlConfiguration.md) — Fixed Wing Longitudinal Control Configuration message + Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages + and configure the resultant setpoints. - [ManualControlSetpoint](ManualControlSetpoint.md) - [ModeCompleted](ModeCompleted.md) — Mode completion result, published by an active mode. The possible values of nav_state are defined in the VehicleStatus msg. @@ -79,8 +92,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [Airspeed](Airspeed.md) -- [AirspeedValidated](AirspeedValidated.md) - - [AirspeedWind](AirspeedWind.md) - [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) @@ -95,7 +106,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [CanInterfaceStatus](CanInterfaceStatus.md) -- [CellularStatus](CellularStatus.md) +- [CellularStatus](CellularStatus.md) — Cellular status - [CollisionConstraints](CollisionConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -164,6 +175,14 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [FigureEightStatus](FigureEightStatus.md) +- [FixedWingLateralGuidanceStatus](FixedWingLateralGuidanceStatus.md) — Fixed Wing Lateral Guidance Status message + Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +- [FixedWingLateralStatus](FixedWingLateralStatus.md) — Fixed Wing Lateral Status message + Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +- [FixedWingRunwayControl](FixedWingRunwayControl.md) — Auxiliary control fields for fixed-wing runway takeoff/landing + - [FlightPhaseEstimation](FlightPhaseEstimation.md) - [FollowTarget](FollowTarget.md) @@ -270,8 +289,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md) -- [NpfgStatus](NpfgStatus.md) - - [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor. - [OffboardControlMode](OffboardControlMode.md) — Off-board control mode @@ -343,6 +360,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverAttitudeStatus](RoverAttitudeStatus.md) +- [RoverPositionSetpoint](RoverPositionSetpoint.md) + - [RoverRateSetpoint](RoverRateSetpoint.md) - [RoverRateStatus](RoverRateStatus.md) @@ -351,6 +370,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) +- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) + - [RoverVelocityStatus](RoverVelocityStatus.md) - [Rpm](Rpm.md) @@ -419,6 +440,9 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [TimesyncStatus](TimesyncStatus.md) +- [TrajectorySetpoint6dof](TrajectorySetpoint6dof.md) — Trajectory setpoint in NED frame + Input to position controller. + - [TransponderReport](TransponderReport.md) - [TuneControl](TuneControl.md) — This message is used to control the tunes, when the tune_id is set to CUSTOM @@ -471,4 +495,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [YawEstimatorStatus](YawEstimatorStatus.md) +- [AirspeedValidatedV0](AirspeedValidatedV0.md) + +- [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md) + - [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander \ No newline at end of file diff --git a/docs/ko/ros2/px4_ros2_control_interface.md b/docs/ko/ros2/px4_ros2_control_interface.md index 77f7a871ff..4c2d03a900 100644 --- a/docs/ko/ros2/px4_ros2_control_interface.md +++ b/docs/ko/ros2/px4_ros2_control_interface.md @@ -345,6 +345,7 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: - [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -359,7 +360,7 @@ You can add your own setpoint types by adding a class that inherits from `px4_ro This setpoint type is currently only supported for multicopters. ::: -Smoothly control position and (optionally) heading setpoints with the [px4_ros2::GotoSetpointType](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. The most trivial use is simply inputting a 3D position into the update method: @@ -404,6 +405,137 @@ _goto_setpoint->update( max_heading_rate_rad_s); ``` +#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) + + + +:::info +This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. +::: + +Use the [`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html) to directly control the lateral and longitudinal dynamics of a fixed-wing vehicle — that is, side-to-side motion (turning/banking) and forward/vertical motion (speeding up and climbing/descending), respectively. +This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../modules/modules_controller.md#fw-lat-lon-control), which decouples lateral and longitudinal inputs while ensuring that vehicle limits are respected. + +To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: + +1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. + If both are set to `NAN`, the vehicle will maintain its current altitude. +2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. + +For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). + +##### 기본 사용법 + +This type has a number of update methods, each allowing you to specify an increasing number of setpoints. + +The simplest method is `updateWithAltitude()`, which allows you to specify a `course` and `altitude` target setpoint: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, course); +``` + +PX4 uses the setpoints to compute the _roll angle_, _pitch angle_ and _throttle_ setpoints that are sent to lower level controllers. +Note that the commanded flight is expected to be relatively gentle/unaggressive when using this method. +This is done as follows: + +- Lateral control output: + + course setpoint (set by user) → airspeed direction (heading) setpoint → lateral acceleration setpoint → roll angle setpoint. + +- Longitudinal control output: + + altitude setpoint (set by user) → height rate setpoint → pitch angle setpoint and throttle settings. + +The `updateWithHeightRate()` method allows you to set a target `course` and `height_rate` (this is useful if the speed of ascent or descent matters, or needs to be dynamically controlled): + +```cpp +const float height_rate = 2.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithHeightRate(height_rate, course); +``` + +The `updateWithAltitude()` and `updateWithHeightRate()` methods allow you to additionally control the equivalent airspeed or lateral acceleration by specifying them as the third and fourth arguments, respectively: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +const float equivalent_aspd = 15.F; // m/s +const float lateral_acceleration = 2.F; // FRD, used as feedforward + +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, + course, + equivalent_aspd, + lateral_acceleration); +``` + +The equivalent airspeed and lateral acceleration arguments are defined as `std::optional`, so you can omit any of them by passing `std::nullopt`. + +:::tip +If both lateral acceleration and course setpoints are provided, the lateral acceleration setpoint will be used as feedforward. +::: + +##### Full Control Using the Setpoint Struct + +For full flexibility, you can create and pass a [`FwLateralLongitudinalSetpoint`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwLateralLongitudinalSetpoint.html) struct. +Each field is templated with `std::optional`. + +:::tip +If both course and airspeed direction are set: airspeed direction takes precedence, course is not controlled. +Lateral acceleration is treated as feedforward if either course or airspeed direction are also finite. +If both altitude and height rate are set: height rate takes precedence, altitude is not controlled. +::: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withCourse(0.F); +// setpoint_s.withAirspeedDirection(0.2F); // uncontrolled +setpoint_s.withLateralAcceleration(2.F); // feedforward +//setpoint_s.withAltitude(500.F); // uncontrolled +setpoint_s.withHeightRate(2.F); +setpoint_s.withEquivalentAirspeed(15.F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s); +``` + +The diagram below illustrates the interaction between the `FwLateralLongitudinalSetpointType` and PX4 when all inputs are set. + +![FW ROS Interaction](../../assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg) + +##### Advanced Configuration (Optional) + +You can also pass a [`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) struct along with the setpoint to override default controller settings and constraints such as pitch limits, throttle limits, and target sink/climb rates. +This is intended for advanced users: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withAirspeedDirection(0.F); +setpoint_s.withLateralAcceleration(2.F); // feedforward +setpoint_s.withAltitude(500.F); +setpoint_s.withEquivalentAirspeed(15.F); + +px4_ros2::FwControlConfiguration config_s; + +config_s.withTargetClimbRate(3.F); +config_s.withMaxAcceleration(5.F); +config_s.withThrottleLimits(0.4F, 0.6F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); +``` + +All configuration fields are defined as `std::optional`. +Unset values will default to the PX4 configuration. +See [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) and [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md) for more information on configuration options. + +:::info +For safety, PX4 automatically limits configuration values to stay within the vehicle’s constraints. +For example, throttle overrides are clamped to remain between [`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) +and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). +::: + #### Direct Actuator Control Setpoint (DirectActuatorsSetpointType) Actuators can be directly controlled using the [px4_ros2::DirectActuatorsSetpointType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) setpoint type. @@ -415,11 +547,55 @@ For example to control a quadrotor, you need to set the first 4 motors according If you want to control an actuator that does not control the vehicle's motion, but for example a payload servo, see [below](#controlling-an-independent-actuator-servo). ::: +### Controlling a VTOL + + + +To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: + +- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). + +As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. + +If you would like to command a VTOL transition in your external mode, you need to use the [VTOL API](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1VTOL.html). The VTOL API provides the functionality to command a transition and query the current state of the vehicle. + +Use this API with caution! +Commanding transitions externally makes the user partially responsible for ensuring smooth and safe behavior, unlike onboard transitions (e.g. via RC switch) where PX4 handles the full process: + +1. Ensure that both the `TrajectorySetpointType` and the `FwLateralLongitudinalSetpointType` are available to your mode. +2. Create an instance of `px4_ros2::VTOL` in the constructor of your mode. +3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. +4. During transition, send the following combination of setpoints: + + ```cpp + // Assuming the instance of the px4_ros2::VTOL object is called vtol + + // Send TrajectorySetpointType as follows: + Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); + Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; + + _trajectory_setpoint->update(velocity_sp, acceleration_sp); + + // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired + + float course_sp = 0.F; // North + + _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) + ``` + + This will ensure that the transition is handled properly within PX4. + You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + +To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. + +See [this external flight mode implementation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol) for a practical example on how to use this API. + ### Controlling an Independent Actuator/Servo If you want to control an independent actuator (a servo), follow these steps: -1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink) +1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). 2. Create an instance of [px4_ros2::PeripheralActuatorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html) in the constructor of your mode. 3. Call the `set()` method to control the actuator(s). This can be done independently of any active setpoints. @@ -431,6 +607,7 @@ You can access PX4 telemetry topics directly via the following classes: - [OdometryGlobalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryGlobalPosition.html): Global position - [OdometryLocalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryLocalPosition.html): Local position, velocity, acceleration, and heading - [OdometryAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAttitude.html): Vehicle attitude +- [OdometryAirspeed](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAirspeed.html): Airspeed For example, you can query the vehicle's current position estimate as follows: diff --git a/docs/ko/sim_gazebo_gz/index.md b/docs/ko/sim_gazebo_gz/index.md index a106d313e8..719e773305 100644 --- a/docs/ko/sim_gazebo_gz/index.md +++ b/docs/ko/sim_gazebo_gz/index.md @@ -396,6 +396,11 @@ As long as the world file and the model file are in the Gazebo search path (`GZ_ However, `make px4_sitl gz__` won't work with them. ::: +## Extending Gazebo with Plugins + +World, vehicle (model), and sensor behaviour can be customised using plugins. +For more information see [Gazebo Plugins](../sim_gazebo_gz/plugins.md). + ## 다중 차량 시뮬레이션 Multi-Vehicle simulation is supported on Linux hosts. diff --git a/docs/ko/sim_gazebo_gz/plugins.md b/docs/ko/sim_gazebo_gz/plugins.md new file mode 100644 index 0000000000..9723f44177 --- /dev/null +++ b/docs/ko/sim_gazebo_gz/plugins.md @@ -0,0 +1,92 @@ +# Gazebo Plugins + +Gazebo plugins extend the simulator with custom functionality not provided by default. They can be attached to different entity types and allow you to add new sensors, modify world physics, or interact with the simulation environment. + +## Plugin Types + +Plugins can be attached to these entity types: + +- **World** - Global simulation behavior +- **Model** - Specific model functionality +- **Sensor** - Custom sensor implementations +- **Actor** - Dynamic entity behavior + +## Supported Plugins + +PX4 currently supports these plugins: + +- [OpticalFlowSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/optical_flow): Provides optical flow sensor simulation using OpenCV-based flow calculation. +- [GstCameraSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/gstreamer): Streams camera feeds via UDP (RTP/H.264) or RTMP with optional NVIDIA CUDA hardware acceleration. +- [MovingPlatformController](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/moving_platform_controller): Controls moving platforms (ships, trucks, etc.) for takeoff and landing scenarios. + Includes configurable velocity, heading, and random fluctuations. + +## Plugin Registration + +Plugins must be registered in the [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) file to be available in your world: + +```xml + + + + + + + + + + +``` + +## Creating Custom Plugins + +When developing new plugins: + +1. **Follow the plugin architecture** - Implement desired interfaces. + + You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. + The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). + +2. **Register your plugin** - Add it to [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) for discovery. + +3. **Use the custom namespace** - Follow the pattern `custom::YourPluginName`. + +### Example Plugin Structure + +```cpp +class YourCustomSystem : + public gz::sim::System, + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemPostUpdate +{ +public: + void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; + void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; +}; + +// Plugin registration +GZ_ADD_PLUGIN(YourCustomSystem, gz::sim::System, + YourCustomSystem::ISystemPreUpdate, + YourCustomSystem::ISystemPostUpdate) +GZ_ADD_PLUGIN_ALIAS(YourCustomSystem, "custom::YourCustomSystem") +``` + +## Enabling a Plugin + +For world plugins all you need to do is [register the plugin](#plugin-registration) (add it to the `server.config`). +It will then be available to all worlds and vehicles. + +The process for adding vehicle model/sensor plugins is not documented. +This can tracked through [PX4-Autopilot#2493](https://github.com/PX4/PX4-Autopilot/issues/24939). + +## Resources + +- **PX4 Plugins**: [Repository source code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins) +- **Official Gazebo Documentation**: [System Plugins Guide](https://gazebosim.org/api/sim/9/createsystemplugins.html) +- **Server Configuration**: [Configuration Reference](https://gazebosim.org/api/sim/9/server_config.html) +- **PX4 Gazebo-classic Plugins**: [PX4 Gazebo Classic Plugins](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/main/src) + +:::info +Plugins for modern Gazebo are still evolving. The plugin system differs from Gazebo Classic. +::: diff --git a/docs/ko/telemetry/crsf_telemetry.md b/docs/ko/telemetry/crsf_telemetry.md index 166fa44117..f4cb1b752b 100644 --- a/docs/ko/telemetry/crsf_telemetry.md +++ b/docs/ko/telemetry/crsf_telemetry.md @@ -71,7 +71,7 @@ For ExpressLRS receivers wire to the flight controller UART as shown below (wiri ### Firmware Configuration/Build CRSF telemetry support is not included in any PX4 firmware by default. -To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver.md#crsf-rc) and removes [rc_input](../modules/modules_driver.md#rc-input). +To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver_radio_control.md#crsf-rc) and removes [rc_input](../modules/modules_driver_radio_control.md#rc-input). 단계는 다음과 같습니다: diff --git a/docs/ko/tutorials/linux_sbus.md b/docs/ko/tutorials/linux_sbus.md index 850dd5541f..4e150769f9 100644 --- a/docs/ko/tutorials/linux_sbus.md +++ b/docs/ko/tutorials/linux_sbus.md @@ -10,9 +10,7 @@ For an S.Bus receiver (or encoder - e.g. from Futaba, RadioLink, etc.) you will Then [Start the PX4 RC Driver](#start_driver) on the device, as shown below. - - -## 드라이버 시작 +## Starting the Driver {#start_driver} To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): @@ -20,11 +18,9 @@ To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): rc_input start -d /dev/ttyS2 ``` -For other driver usage information see: [rc_input](../modules/modules_driver.md#rc-input). +For other driver usage information see: [rc_input](../modules/modules_driver_radio_control.md#rc-input). - - -## 신호 반전 회로(S.Bus 전용) +## Signal Inverter Circuit (S.Bus only) {#signal_inverter_circuit} S.Bus is an _inverted_ UART communication signal. From 8204331fa9794e811a2ae64d597a5feeba4e3aa7 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Mon, 2 Jun 2025 07:43:29 +1000 Subject: [PATCH 078/130] New Crowdin translations - uk (#24949) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 20 +- docs/uk/concept/events_interface.md | 2 +- docs/uk/config/safety.md | 19 +- docs/uk/contribute/docs.md | 16 +- docs/uk/flight_modes_fw/land.md | 11 +- docs/uk/flight_modes_fw/takeoff.md | 42 +-- docs/uk/frames_plane/reptile_dragon_2.md | 2 +- docs/uk/middleware/uxrce_dds.md | 4 + docs/uk/modules/modules_controller.md | 32 ++- docs/uk/modules/modules_driver.md | 4 +- docs/uk/modules/modules_system.md | 1 + docs/uk/msg_docs/AirspeedValidated.md | 26 +- docs/uk/msg_docs/AirspeedValidatedV0.md | 25 ++ docs/uk/msg_docs/CellularStatus.md | 64 +++-- .../FixedWingLateralGuidanceStatus.md | 23 ++ docs/uk/msg_docs/FixedWingLateralSetpoint.md | 22 ++ docs/uk/msg_docs/FixedWingLateralStatus.md | 17 ++ .../msg_docs/FixedWingLongitudinalSetpoint.md | 26 ++ docs/uk/msg_docs/FixedWingRunwayControl.md | 19 ++ .../msg_docs/LateralControlConfiguration.md | 18 ++ .../LongitudinalControlConfiguration.md | 28 ++ docs/uk/msg_docs/PurePursuitStatus.md | 2 - docs/uk/msg_docs/RateCtrlStatus.md | 1 - docs/uk/msg_docs/RoverAttitudeSetpoint.md | 2 - docs/uk/msg_docs/RoverAttitudeStatus.md | 2 - docs/uk/msg_docs/RoverPositionSetpoint.md | 15 + docs/uk/msg_docs/RoverRateSetpoint.md | 2 - docs/uk/msg_docs/RoverRateStatus.md | 2 - docs/uk/msg_docs/RoverSteeringSetpoint.md | 5 +- docs/uk/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/uk/msg_docs/RoverVelocitySetpoint.md | 12 + docs/uk/msg_docs/RoverVelocityStatus.md | 10 +- docs/uk/msg_docs/TrajectorySetpoint6dof.md | 23 ++ docs/uk/msg_docs/VehicleAttitudeSetpoint.md | 6 +- docs/uk/msg_docs/VehicleAttitudeSetpointV0.md | 25 ++ docs/uk/msg_docs/VehicleCommand.md | 256 +++++++++--------- docs/uk/msg_docs/index.md | 38 ++- docs/uk/ros2/px4_ros2_control_interface.md | 181 ++++++++++++- docs/uk/sim_gazebo_gz/index.md | 5 + docs/uk/sim_gazebo_gz/plugins.md | 92 +++++++ docs/uk/telemetry/crsf_telemetry.md | 2 +- docs/uk/tutorials/linux_sbus.md | 10 +- 42 files changed, 865 insertions(+), 253 deletions(-) create mode 100644 docs/uk/msg_docs/AirspeedValidatedV0.md create mode 100644 docs/uk/msg_docs/FixedWingLateralGuidanceStatus.md create mode 100644 docs/uk/msg_docs/FixedWingLateralSetpoint.md create mode 100644 docs/uk/msg_docs/FixedWingLateralStatus.md create mode 100644 docs/uk/msg_docs/FixedWingLongitudinalSetpoint.md create mode 100644 docs/uk/msg_docs/FixedWingRunwayControl.md create mode 100644 docs/uk/msg_docs/LateralControlConfiguration.md create mode 100644 docs/uk/msg_docs/LongitudinalControlConfiguration.md create mode 100644 docs/uk/msg_docs/RoverPositionSetpoint.md create mode 100644 docs/uk/msg_docs/RoverVelocitySetpoint.md create mode 100644 docs/uk/msg_docs/TrajectorySetpoint6dof.md create mode 100644 docs/uk/msg_docs/VehicleAttitudeSetpointV0.md create mode 100644 docs/uk/sim_gazebo_gz/plugins.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index 59a0844b23..86d0b93703 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -459,6 +459,7 @@ - [Vehicles](sim_gazebo_gz/vehicles.md) - [Advanced Lift Drag Tool](sim_gazebo_gz/tools_avl_automation.md) - [Worlds](sim_gazebo_gz/worlds.md) + - [Plugins](sim_gazebo_gz/plugins.md) - [Gazebo Models Repository](sim_gazebo_gz/gazebo_models.md) - [Багатотранспортний Sim](sim_gazebo_gz/multi_vehicle_simulation.md) - [Симуляція Gazebo Classic](sim_gazebo_classic/index.md) @@ -491,12 +492,17 @@ - [Versioned](msg_docs/versioned_messages.md) - [ActuatorMotors](msg_docs/ActuatorMotors.md) - [ActuatorServos](msg_docs/ActuatorServos.md) + - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [ArmingCheckReply](msg_docs/ArmingCheckReply.md) - [ArmingCheckRequest](msg_docs/ArmingCheckRequest.md) - [BatteryStatus](msg_docs/BatteryStatus.md) - [ConfigOverrides](msg_docs/ConfigOverrides.md) + - [FixedWingLateralSetpoint](msg_docs/FixedWingLateralSetpoint.md) + - [FixedWingLongitudinalSetpoint](msg_docs/FixedWingLongitudinalSetpoint.md) - [GotoSetpoint](msg_docs/GotoSetpoint.md) - [HomePosition](msg_docs/HomePosition.md) + - [LateralControlConfiguration](msg_docs/LateralControlConfiguration.md) + - [LongitudinalControlConfiguration](msg_docs/LongitudinalControlConfiguration.md) - [ManualControlSetpoint](msg_docs/ManualControlSetpoint.md) - [ModeCompleted](msg_docs/ModeCompleted.md) - [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md) @@ -525,10 +531,8 @@ - [ActuatorTest](msg_docs/ActuatorTest.md) - [AdcReport](msg_docs/AdcReport.md) - [Airspeed](msg_docs/Airspeed.md) - - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [AirspeedWind](msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](msg_docs/AutotuneAttitudeControlStatus.md) - - [Buffer128](msg_docs/Buffer128.md) - [ButtonEvent](msg_docs/ButtonEvent.md) - [CameraCapture](msg_docs/CameraCapture.md) - [CameraStatus](msg_docs/CameraStatus.md) @@ -567,6 +571,9 @@ - [FailsafeFlags](msg_docs/FailsafeFlags.md) - [FailureDetectorStatus](msg_docs/FailureDetectorStatus.md) - [FigureEightStatus](msg_docs/FigureEightStatus.md) + - [FixedWingLateralGuidanceStatus](msg_docs/FixedWingLateralGuidanceStatus.md) + - [FixedWingLateralStatus](msg_docs/FixedWingLateralStatus.md) + - [FixedWingRunwayControl](msg_docs/FixedWingRunwayControl.md) - [FlightPhaseEstimation](msg_docs/FlightPhaseEstimation.md) - [FollowTarget](msg_docs/FollowTarget.md) - [FollowTargetEstimator](msg_docs/FollowTargetEstimator.md) @@ -619,7 +626,6 @@ - [NavigatorMissionItem](msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](msg_docs/NavigatorStatus.md) - [NormalizedUnsignedSetpoint](msg_docs/NormalizedUnsignedSetpoint.md) - - [NpfgStatus](msg_docs/NpfgStatus.md) - [ObstacleDistance](msg_docs/ObstacleDistance.md) - [OffboardControlMode](msg_docs/OffboardControlMode.md) - [OnboardComputerStatus](msg_docs/OnboardComputerStatus.md) @@ -655,13 +661,12 @@ - [RcParameterMap](msg_docs/RcParameterMap.md) - [RoverAttitudeSetpoint](msg_docs/RoverAttitudeSetpoint.md) - [RoverAttitudeStatus](msg_docs/RoverAttitudeStatus.md) - - [RoverMecanumGuidanceStatus](msg_docs/RoverMecanumGuidanceStatus.md) - - [RoverMecanumSetpoint](msg_docs/RoverMecanumSetpoint.md) - - [RoverMecanumStatus](msg_docs/RoverMecanumStatus.md) + - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) + - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) - [RoverVelocityStatus](msg_docs/RoverVelocityStatus.md) - [Rpm](msg_docs/Rpm.md) - [RtlStatus](msg_docs/RtlStatus.md) @@ -693,6 +698,7 @@ - [TelemetryStatus](msg_docs/TelemetryStatus.md) - [TiltrotorExtraControls](msg_docs/TiltrotorExtraControls.md) - [TimesyncStatus](msg_docs/TimesyncStatus.md) + - [TrajectorySetpoint6dof](msg_docs/TrajectorySetpoint6dof.md) - [TransponderReport](msg_docs/TransponderReport.md) - [TuneControl](msg_docs/TuneControl.md) - [UavcanParameterRequest](msg_docs/UavcanParameterRequest.md) @@ -716,6 +722,8 @@ - [WheelEncoders](msg_docs/WheelEncoders.md) - [Wind](msg_docs/Wind.md) - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) + - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) + - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - [Повідомлення MAVLink](middleware/mavlink.md) - [Adding Messages](mavlink/adding_messages.md) diff --git a/docs/uk/concept/events_interface.md b/docs/uk/concept/events_interface.md index ccac5195f7..b0c861c861 100644 --- a/docs/uk/concept/events_interface.md +++ b/docs/uk/concept/events_interface.md @@ -175,4 +175,4 @@ Events can have a fixed set of arguments that can be inserted into the message o Для отримання додаткової інформації див. Метадані PX4 (трансляція і публікація). Цей процес такий самий як і для [метаданих параметрів](../advanced/parameters_and_configurations.md#publishing-parameter-metadata-to-a-gcs). -Для отримання додаткової інформації див. [Метадані PX4 (трансляція і публікація)](../advanced/px4_metadata.md) +For more information see [PX4 Metadata (Translation & Publication)](../advanced/px4_metadata.md) diff --git a/docs/uk/config/safety.md b/docs/uk/config/safety.md index 3637702f20..1fae88595d 100644 --- a/docs/uk/config/safety.md +++ b/docs/uk/config/safety.md @@ -185,7 +185,24 @@ Due to the inherent danger of this, this function is disabled using [CBRK_FLIGHT ## Position (GNSS) Loss Failsafe -The _Position Loss Failsafe_ is triggered if the quality of the PX4 global position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The _Position Loss Failsafe_ is triggered if the quality of the PX4 position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The sections below cover first the trigger and then the failsafe action taken by the controller. + +### Position Loss Failsafe Trigger + +There are basically two mechanisms in PX4 to trigger position failsafes: + +- A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. +- The estimated horizontal position accuracy exceeds a certain threshold. This check is only done on hovering systems (rotary wing vehicles or VTOLs in hover phase). + +The relevant parameters shown below. + +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [EKF2_NOAID_TOUT](../advanced_config/parameter_reference.md#EKF2_NOAID_TOUT) | Maximum inertial dead-reckoning time, so the time after the last data sample was received of any sensor that constrains the velocity drift [microseconds]. | +| [COM_POS_FS_EPH](../advanced_config/parameter_reference.md#COM_POS_FS_EPH) | Horizontal position error threshold for hovering vehicles (Multicopters and VTOLs in hover). Fixed-wing vehicles have this value set to infinity. | + +### Position Loss Failsafe Action The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): diff --git a/docs/uk/contribute/docs.md b/docs/uk/contribute/docs.md index 5de5d30fbb..98f74dc95e 100644 --- a/docs/uk/contribute/docs.md +++ b/docs/uk/contribute/docs.md @@ -181,11 +181,19 @@ Within the repository you created above: 5. Open previewed pages in your local editor: First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. - For example, on Windows command line you can enable VSCode as your default editor by entering: + For example, you can enable VSCode as your default editor by entering: - ```sh - set EDITOR=code - ``` + - Windows: + + ```sh + set EDITOR=code + ``` + + - Linux: + + ```sh + export EDITOR=code + ``` The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). diff --git a/docs/uk/flight_modes_fw/land.md b/docs/uk/flight_modes_fw/land.md index 8e13cca8b7..0ce3f24bfb 100644 --- a/docs/uk/flight_modes_fw/land.md +++ b/docs/uk/flight_modes_fw/land.md @@ -41,11 +41,12 @@ The vehicle will flare if configured to do so (see [Flaring](../flight_modes_fw/ Поведінку режиму приземлення можна налаштувати за допомогою наведених нижче параметрів. -| Параметр | Опис | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------- | -| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | Радіус блукання, який контролер відстежує протягом усієї послідовності посадки. | -| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | Виставте кут шляху пункту налаштувань. | -| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | Налаштування швидкості. | +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | Радіус блукання, який контролер відстежує протягом усієї послідовності посадки. | +| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | Виставте кут шляху пункту налаштувань. | +| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | Налаштування швидкості. | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. | ## Дивіться також diff --git a/docs/uk/flight_modes_fw/takeoff.md b/docs/uk/flight_modes_fw/takeoff.md index f83346f027..dade7341cf 100644 --- a/docs/uk/flight_modes_fw/takeoff.md +++ b/docs/uk/flight_modes_fw/takeoff.md @@ -43,13 +43,14 @@ Reaching the clearance altitude causes the vehicle to enter [Hold mode](../fligh Параметри, які впливають як на катапульту/ручний старт, так і на зліт зі злітно-посадкової смуги: -| Параметр | Опис | -| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Мінімальна висота встановлення над будинком, на яку підніметься транспортний засіб під час зльоту. | -| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) | -| [FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | Це мінімальний кут нахилу заданий під час фази зльоту | -| [FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Максимальний кут підйому. | -| [FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Налаштування закрилок під час зльоту | +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Мінімальна висота встановлення над будинком, на яку підніметься транспортний засіб під час зльоту. | +| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) | +| [FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | Це мінімальний кут нахилу заданий під час фази зльоту | +| [FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Максимальний кут підйому. | +| [FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Налаштування закрилок під час зльоту | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_TKO_AIRSPD is below FW_AIRSPD_MIN. | :::info The vehicle always respects normal FW max/min throttle settings during takeoff ([FW_THR_MIN](../advanced_config/parameter_reference.md#FW_THR_MIN), [FW_THR_MAX](../advanced_config/parameter_reference.md#FW_THR_MAX)). @@ -101,26 +102,25 @@ The _runway takeoff mode_ has the following phases: :::info For a smooth takeoff, the runway wheel controller possibly needs to be tuned. -It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)) and an outer loop that calculates heading setpoints from course errors and can be tuned via [RWTO_NPFG_PERIOD](#RWTO_NPFG_PERIOD). +It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)). ::: ### Параметри (зліт зі злітної смуги) Зліт зі злітної смуги залежить від наступних параметрів: -| Параметр | Опис | -| ----------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Увімкніть зліт по взлітній смузі | -| [FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Увімкнути контролер колеса | -| [RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Максимальне розгін під час взліту зі злітної смуги | -| [RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Час прискорення ручки газу | -| [RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Поріг швидкості для початку підняття (нахилення вгору). Якщо не налаштовано оператором, встановлюється на 0,9\*FW_TKO_AIRSPD. | -| [RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | Це час, який необхідно лінійно нарощувати обмеження швидкості прийому під час обертання на зльоті. | -| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Задана швидкість під час розгону під час зльоту (після відкочування). Якщо не налаштовано оператором, встановлюється на FW_AIRSPD_MIN. | -| [RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Увімкніть керування колесом під час руху по злітній смузі | -| [FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | Розмах крила транспортного засобу. Використовується для запобігання ударів крилом. | -| [FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | Висота крил над землею (дорожній просвіт). Використовується для запобігання ударів крилом. | -| [RWTO_NPFG_PERIOD](../advanced_config/parameter_reference.md#RWTO_NPFG_PERIOD) | Час L1 під час керування на злітній смузі. Збільшення для менш агресивної відповіді на помилки курсу. | +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Увімкніть зліт по взлітній смузі | +| [FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Увімкнути контролер колеса | +| [RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Максимальне розгін під час взліту зі злітної смуги | +| [RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Час прискорення ручки газу | +| [RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Поріг швидкості для початку підняття (нахилення вгору). Якщо не налаштовано оператором, встановлюється на 0,9\*FW_TKO_AIRSPD. | +| [RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | Це час, який необхідно лінійно нарощувати обмеження швидкості прийому під час обертання на зльоті. | +| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Задана швидкість під час розгону під час зльоту (після відкочування). Якщо не налаштовано оператором, встановлюється на FW_AIRSPD_MIN. | +| [RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Увімкніть керування колесом під час руху по злітній смузі | +| [FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | Розмах крила транспортного засобу. Використовується для запобігання ударів крилом. | +| [FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | Висота крил над землею (дорожній просвіт). Використовується для запобігання ударів крилом. | ## Дивіться також diff --git a/docs/uk/frames_plane/reptile_dragon_2.md b/docs/uk/frames_plane/reptile_dragon_2.md index c65111cda7..3f65bb3a4e 100644 --- a/docs/uk/frames_plane/reptile_dragon_2.md +++ b/docs/uk/frames_plane/reptile_dragon_2.md @@ -325,7 +325,7 @@ ELRS RX був прикріплений до бічної стінки корп ## Збірка прошивки -You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. +You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver_radio_control.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. Для їх використання потрібна деяка налаштування. diff --git a/docs/uk/middleware/uxrce_dds.md b/docs/uk/middleware/uxrce_dds.md index 62eac42e83..6c545dbf6e 100644 --- a/docs/uk/middleware/uxrce_dds.md +++ b/docs/uk/middleware/uxrce_dds.md @@ -435,9 +435,11 @@ publications: - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry + rate_limit: 150. - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus + rate_limit: 50. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint @@ -472,6 +474,8 @@ Each (`topic`,`type`) pairs defines: - `/fmu/out/` for topics that are _published_ by PX4. - `/fmu/in/` for topics that are _subscribed_ by PX4. 4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition. +5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2. + If left unspecified, the maximum publication rate limit is set to 100 Hz. `subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively. Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers. diff --git a/docs/uk/modules/modules_controller.md b/docs/uk/modules/modules_controller.md index 6ae0e1a0b1..32a347a826 100644 --- a/docs/uk/modules/modules_controller.md +++ b/docs/uk/modules/modules_controller.md @@ -91,18 +91,18 @@ fw_att_control [arguments...] status print status info ``` -## fw_pos_control +## fw_lat_lon_control -Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_pos_control) +Source: [modules/fw_lateral_longitudinal_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_lateral_longitudinal_control) ### Опис -fw_pos_control is the fixed-wing position controller. +fw_lat_lon_control computes attitude and throttle setpoints from lateral and longitudinal control setpoints. -### Usage {#fw_pos_control_usage} +### Usage {#fw_lat_lon_control_usage} ``` -fw_pos_control [arguments...] +fw_lat_lon_control [arguments...] Commands: start [vtol] VTOL mode @@ -112,6 +112,28 @@ fw_pos_control [arguments...] status print status info ``` +## fw_mode_manager + +Source: [modules/fw_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_mode_manager) + +### Опис + +This implements the setpoint generation for all PX4-internal fixed-wing modes, height-rate control and higher. +It takes the current mode state of the vehicle as input and outputs setpoints consumed by the fixed-wing +lateral-longitudinal controller and and controllers below that (attitude, rate). + +### Usage {#fw_mode_manager_usage} + +``` +fw_mode_manager [arguments...] + Commands: + start + + stop + + status print status info +``` + ## fw_rate_control Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_rate_control) diff --git a/docs/uk/modules/modules_driver.md b/docs/uk/modules/modules_driver.md index 59002c651e..f5ad565475 100644 --- a/docs/uk/modules/modules_driver.md +++ b/docs/uk/modules/modules_driver.md @@ -293,7 +293,9 @@ dshot [arguments...] start telemetry Enable Telemetry on a UART - UART device + -d UART device + values: + [-x] Swap RX/TX pins reverse Reverse motor direction [-m ] Motor index (1-based, default=all) diff --git a/docs/uk/modules/modules_system.md b/docs/uk/modules/modules_system.md index f0f23b9ff7..43c883ed66 100644 --- a/docs/uk/modules/modules_system.md +++ b/docs/uk/modules/modules_system.md @@ -318,6 +318,7 @@ i2c_launcher [arguments...] Commands: start -b Bus number + -t battery index for calibration values (1 or 3) stop diff --git a/docs/uk/msg_docs/AirspeedValidated.md b/docs/uk/msg_docs/AirspeedValidated.md index 0de1450e5b..41bfe31f09 100644 --- a/docs/uk/msg_docs/AirspeedValidated.md +++ b/docs/uk/msg_docs/AirspeedValidated.md @@ -1,21 +1,27 @@ # AirspeedValidated (повідомлення UORB) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AirspeedValidated.msg) +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +uint32 MESSAGE_VERSION = 1 + uint64 timestamp # time since system start (microseconds) -float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid -float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid +float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +int8 airspeed_source # Source of currently published airspeed values +int8 DISABLED = -1 +int8 GROUND_MINUS_WIND = 0 +int8 SENSOR_1 = 1 +int8 SENSOR_2 = 2 +int8 SENSOR_3 = 3 +int8 SYNTHETIC = 4 + +# debug states float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid - -bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. - -int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid - +float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] float32 throttle_filtered # filtered fixed-wing throttle [-] float32 pitch_filtered # filtered pitch [rad] diff --git a/docs/uk/msg_docs/AirspeedValidatedV0.md b/docs/uk/msg_docs/AirspeedValidatedV0.md new file mode 100644 index 0000000000..8bca98a224 --- /dev/null +++ b/docs/uk/msg_docs/AirspeedValidatedV0.md @@ -0,0 +1,25 @@ +# AirspeedValidatedV0 (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/AirspeedValidatedV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid +float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid + +float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid +float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid + +bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. + +int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid + +float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] +float32 throttle_filtered # filtered fixed-wing throttle [-] +float32 pitch_filtered # filtered pitch [rad] + +``` diff --git a/docs/uk/msg_docs/CellularStatus.md b/docs/uk/msg_docs/CellularStatus.md index bb98146320..603600fa8d 100644 --- a/docs/uk/msg_docs/CellularStatus.md +++ b/docs/uk/msg_docs/CellularStatus.md @@ -1,35 +1,49 @@ # CellularStatus (повідомлення UORB) +Cellular status + +This is currently used only for logging cell status from MAVLink. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CellularStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Cellular status +# +# This is currently used only for logging cell status from MAVLink. -uint8 CELLULAR_STATUS_FLAG_UNKNOWN=0 # State unknown or not reportable -uint8 CELLULAR_STATUS_FLAG_FAILED=1 # velocity setpoint -uint8 CELLULAR_STATUS_FLAG_INITIALIZING=2 # Modem is being initialized -uint8 CELLULAR_STATUS_FLAG_LOCKED=3 # Modem is locked -uint8 CELLULAR_STATUS_FLAG_DISABLED=4 # Modem is not enabled and is powered down -uint8 CELLULAR_STATUS_FLAG_DISABLING=5 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLING=6 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLED=7 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint8 CELLULAR_STATUS_FLAG_SEARCHING=8 # Modem is searching for a network provider to register -uint8 CELLULAR_STATUS_FLAG_REGISTERED=9 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint8 CELLULAR_STATUS_FLAG_DISCONNECTING=10 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint8 CELLULAR_STATUS_FLAG_CONNECTING=11 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint8 CELLULAR_STATUS_FLAG_CONNECTED=12 # One or more packet data bearers is active and connected +uint64 timestamp # [us] Time since system start. -uint8 CELLULAR_NETWORK_FAILED_REASON_NONE=0 # No error -uint8 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN=1 # Error state is unknown -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING=2 # SIM is required for the modem but missing -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3 # SIM is available, but not usable for connection +uint16 status # [@enum STATUS_FLAG] Status bitmap. +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable. +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable. +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized. +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked. +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down. +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state. +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state. +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections. +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register. +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use. +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated. +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered. +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected. -uint16 status # Status bitmap 1: Roaming is active -uint8 failure_reason #Failure reason when status in in CELLUAR_STATUS_FAILED -uint8 type # Cellular network radio type 0: none 1: gsm 2: cdma 3: wcdma 4: lte -uint8 quality # Cellular network RSSI/RSRP in dBm, absolute value -uint16 mcc # Mobile country code. If unknown, set to: UINT16_MAX -uint16 mnc # Mobile network code. If unknown, set to: UINT16_MAX -uint16 lac # Location area code. If unknown, set to: 0 +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason. +uint8 FAILURE_REASON_NONE = 0 # No error. +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown. +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing. +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection. + +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type. +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE + +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value. +uint16 mcc # [@invalid UINT16_MAX] Mobile country code. +uint16 mnc # [@invalid UINT16_MAX] Mobile network code. +uint16 lac # [@invalid 0] Location area code. ``` diff --git a/docs/uk/msg_docs/FixedWingLateralGuidanceStatus.md b/docs/uk/msg_docs/FixedWingLateralGuidanceStatus.md new file mode 100644 index 0000000000..02dc50b410 --- /dev/null +++ b/docs/uk/msg_docs/FixedWingLateralGuidanceStatus.md @@ -0,0 +1,23 @@ +# FixedWingLateralGuidanceStatus (UORB message) + +Fixed Wing Lateral Guidance Status message +Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralGuidanceStatus.msg) + +```c +# Fixed Wing Lateral Guidance Status message +# Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +uint64 timestamp # time since system start (microseconds) + +float32 course_setpoint # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. Set by guidance law +float32 lateral_acceleration_ff # [m/s^2] [FRD] lateral acceleration demand only for maintaining curvature +float32 bearing_feas # [@range 0,1] bearing feasibility +float32 bearing_feas_on_track # [@range 0,1] on-track bearing feasibility +float32 signed_track_error # [m] signed track error +float32 track_error_bound # [m] track error bound +float32 adapted_period # [s] adapted period (if auto-tuning enabled) +uint8 wind_est_valid # [boolean] true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) + +``` diff --git a/docs/uk/msg_docs/FixedWingLateralSetpoint.md b/docs/uk/msg_docs/FixedWingLateralSetpoint.md new file mode 100644 index 0000000000..153167bb62 --- /dev/null +++ b/docs/uk/msg_docs/FixedWingLateralSetpoint.md @@ -0,0 +1,22 @@ +# FixedWingLateralSetpoint (UORB message) + +Fixed Wing Lateral Setpoint message +Used by the fw_lateral_longitudinal_control module +At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLateralSetpoint.msg) + +```c +# Fixed Wing Lateral Setpoint message +# Used by the fw_lateral_longitudinal_control module +# At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. +float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. +float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. + +``` diff --git a/docs/uk/msg_docs/FixedWingLateralStatus.md b/docs/uk/msg_docs/FixedWingLateralStatus.md new file mode 100644 index 0000000000..9214d1e9e0 --- /dev/null +++ b/docs/uk/msg_docs/FixedWingLateralStatus.md @@ -0,0 +1,17 @@ +# FixedWingLateralStatus (UORB message) + +Fixed Wing Lateral Status message +Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralStatus.msg) + +```c +# Fixed Wing Lateral Status message +# Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_acceleration_setpoint # [m/s^2] [FRD] resultant lateral acceleration setpoint +float32 can_run_factor # [norm] [@range 0, 1] estimate of certainty of the correct functionality of the npfg roll setpoint + +``` diff --git a/docs/uk/msg_docs/FixedWingLongitudinalSetpoint.md b/docs/uk/msg_docs/FixedWingLongitudinalSetpoint.md new file mode 100644 index 0000000000..6b8fb29e5b --- /dev/null +++ b/docs/uk/msg_docs/FixedWingLongitudinalSetpoint.md @@ -0,0 +1,26 @@ +# FixedWingLongitudinalSetpoint (UORB message) + +Fixed Wing Longitudinal Setpoint message +Used by the fw_lateral_longitudinal_control module +If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +If both altitude and height_rate are NAN, the controller maintains the current altitude. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLongitudinalSetpoint.msg) + +```c +# Fixed Wing Longitudinal Setpoint message +# Used by the fw_lateral_longitudinal_control module +# If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +# If both altitude and height_rate are NAN, the controller maintains the current altitude. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite +float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not controlled directly +float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used +float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller +float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller + +``` diff --git a/docs/uk/msg_docs/FixedWingRunwayControl.md b/docs/uk/msg_docs/FixedWingRunwayControl.md new file mode 100644 index 0000000000..9e9f5ff428 --- /dev/null +++ b/docs/uk/msg_docs/FixedWingRunwayControl.md @@ -0,0 +1,19 @@ +# FixedWingRunwayControl (UORB message) + +Auxiliary control fields for fixed-wing runway takeoff/landing + +Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingRunwayControl.msg) + +```c +# Auxiliary control fields for fixed-wing runway takeoff/landing + +# Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +uint64 timestamp # [us] time since system start + +bool wheel_steering_enabled # Flag that enables the wheel steering. +float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. + +``` diff --git a/docs/uk/msg_docs/LateralControlConfiguration.md b/docs/uk/msg_docs/LateralControlConfiguration.md new file mode 100644 index 0000000000..b0a03a6378 --- /dev/null +++ b/docs/uk/msg_docs/LateralControlConfiguration.md @@ -0,0 +1,18 @@ +# LateralControlConfiguration (UORB message) + +Fixed Wing Lateral Control Configuration message +Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LateralControlConfiguration.msg) + +```c +# Fixed Wing Lateral Control Configuration message +# Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY + +``` diff --git a/docs/uk/msg_docs/LongitudinalControlConfiguration.md b/docs/uk/msg_docs/LongitudinalControlConfiguration.md new file mode 100644 index 0000000000..901d5c23bc --- /dev/null +++ b/docs/uk/msg_docs/LongitudinalControlConfiguration.md @@ -0,0 +1,28 @@ +# LongitudinalControlConfiguration (UORB message) + +Fixed Wing Longitudinal Control Configuration message +Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +and configure the resultant setpoints. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LongitudinalControlConfiguration.msg) + +```c +# Fixed Wing Longitudinal Control Configuration message +# Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +# and configure the resultant setpoints. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 pitch_min # [rad][@range -pi, pi] defaults to FW_P_LIM_MIN if NAN. +float32 pitch_max # [rad][@range -pi, pi] defaults to FW_P_LIM_MAX if NAN. +float32 throttle_min # [norm] [@range 0,1] deaults to FW_THR_MIN if NAN. +float32 throttle_max # [norm] [@range 0,1] defaults to FW_THR_MAX if NAN. +float32 climb_rate_target # [m/s] target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only +bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking +bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller + +``` diff --git a/docs/uk/msg_docs/PurePursuitStatus.md b/docs/uk/msg_docs/PurePursuitStatus.md index 76ae5524f0..1685af32d1 100644 --- a/docs/uk/msg_docs/PurePursuitStatus.md +++ b/docs/uk/msg_docs/PurePursuitStatus.md @@ -11,6 +11,4 @@ float32 crosstrack_error # [m] Shortest distance from the vehicle to the pat float32 distance_to_waypoint # [m] Distance from the vehicle to the current waypoint float32 bearing_to_waypoint # [rad] Bearing towards current waypoint -# TOPICS pure_pursuit_status - ``` diff --git a/docs/uk/msg_docs/RateCtrlStatus.md b/docs/uk/msg_docs/RateCtrlStatus.md index c6a4323ae9..90eaa1208f 100644 --- a/docs/uk/msg_docs/RateCtrlStatus.md +++ b/docs/uk/msg_docs/RateCtrlStatus.md @@ -9,6 +9,5 @@ uint64 timestamp # time since system start (microseconds) float32 rollspeed_integ float32 pitchspeed_integ float32 yawspeed_integ -float32 wheel_rate_integ # FW only and optional ``` diff --git a/docs/uk/msg_docs/RoverAttitudeSetpoint.md b/docs/uk/msg_docs/RoverAttitudeSetpoint.md index fc2bc4d639..778d4407a9 100644 --- a/docs/uk/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/uk/msg_docs/RoverAttitudeSetpoint.md @@ -7,6 +7,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_setpoint # [rad] Expressed in NED frame -# TOPICS rover_attitude_setpoint - ``` diff --git a/docs/uk/msg_docs/RoverAttitudeStatus.md b/docs/uk/msg_docs/RoverAttitudeStatus.md index 28d9ef6d96..24dc3cf12f 100644 --- a/docs/uk/msg_docs/RoverAttitudeStatus.md +++ b/docs/uk/msg_docs/RoverAttitudeStatus.md @@ -8,6 +8,4 @@ uint64 timestamp # time since system start (microseconds) float32 measured_yaw # [rad/s] Measured yaw rate float32 adjusted_yaw_setpoint # [rad/s] Yaw setpoint that is being tracked (Applied slew rates) -# TOPICS rover_attitude_status - ``` diff --git a/docs/uk/msg_docs/RoverPositionSetpoint.md b/docs/uk/msg_docs/RoverPositionSetpoint.md new file mode 100644 index 0000000000..8450bf8486 --- /dev/null +++ b/docs/uk/msg_docs/RoverPositionSetpoint.md @@ -0,0 +1,15 @@ +# RoverPositionSetpoint (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32[2] position_ned # 2-dimensional position setpoint in NED frame [m] +float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position) +float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed) +float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero) + +float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw) + +``` diff --git a/docs/uk/msg_docs/RoverRateSetpoint.md b/docs/uk/msg_docs/RoverRateSetpoint.md index 71755a38f3..12fe8cb88c 100644 --- a/docs/uk/msg_docs/RoverRateSetpoint.md +++ b/docs/uk/msg_docs/RoverRateSetpoint.md @@ -7,6 +7,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_rate_setpoint # [rad/s] Expressed in NED frame -# TOPICS rover_rate_setpoint - ``` diff --git a/docs/uk/msg_docs/RoverRateStatus.md b/docs/uk/msg_docs/RoverRateStatus.md index 1f54694ee0..a3aa1d1164 100644 --- a/docs/uk/msg_docs/RoverRateStatus.md +++ b/docs/uk/msg_docs/RoverRateStatus.md @@ -9,6 +9,4 @@ float32 measured_yaw_rate # [rad/s] Measured yaw rate float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint that is being tracked (Applied slew rates) float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller -# TOPICS rover_rate_status - ``` diff --git a/docs/uk/msg_docs/RoverSteeringSetpoint.md b/docs/uk/msg_docs/RoverSteeringSetpoint.md index 1a6f3203dd..48353ea957 100644 --- a/docs/uk/msg_docs/RoverSteeringSetpoint.md +++ b/docs/uk/msg_docs/RoverSteeringSetpoint.md @@ -5,9 +5,8 @@ ```c uint64 timestamp # time since system start (microseconds) -float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Only for Ackermann-steered rovers) -float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Only for Differential/Mecanum rovers) +float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Ackermann only, Positiv: Steer right, Negativ: Steer left) -# TOPICS rover_steering_setpoint +float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Differential/Mecanum only, Positiv = Turn right, Negativ: Turn left) ``` diff --git a/docs/uk/msg_docs/RoverThrottleSetpoint.md b/docs/uk/msg_docs/RoverThrottleSetpoint.md index 9533126dd0..ccdf76902d 100644 --- a/docs/uk/msg_docs/RoverThrottleSetpoint.md +++ b/docs/uk/msg_docs/RoverThrottleSetpoint.md @@ -6,9 +6,7 @@ uint64 timestamp # time since system start (microseconds) -float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] -float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] - -# TOPICS rover_throttle_setpoint +float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] (Positiv = forwards, Negativ = backwards) +float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] (Mecanum only, Positiv = right, Negativ = left) ``` diff --git a/docs/uk/msg_docs/RoverVelocitySetpoint.md b/docs/uk/msg_docs/RoverVelocitySetpoint.md new file mode 100644 index 0000000000..2e2d322b47 --- /dev/null +++ b/docs/uk/msg_docs/RoverVelocitySetpoint.md @@ -0,0 +1,12 @@ +# RoverVelocitySetpoint (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocitySetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative) +float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction] +float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame + +``` diff --git a/docs/uk/msg_docs/RoverVelocityStatus.md b/docs/uk/msg_docs/RoverVelocityStatus.md index 02b2c3b527..c908ffac90 100644 --- a/docs/uk/msg_docs/RoverVelocityStatus.md +++ b/docs/uk/msg_docs/RoverVelocityStatus.md @@ -6,14 +6,10 @@ uint64 timestamp # time since system start (microseconds) float32 measured_speed_body_x # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards -float32 speed_body_x_setpoint # [m/s] Speed setpoint in body x direction. Positiv: forwards, Negativ: backwards float32 adjusted_speed_body_x_setpoint # [m/s] Post slew rate speed setpoint in body x direction. Positiv: forwards, Negativ: backwards -float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left -float32 speed_body_y_setpoint # [m/s] Speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) -float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) float32 pid_throttle_body_x_integral # Integral of the PID for the closed loop controller of the speed in body x direction -float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction - -# TOPICS rover_velocity_status +float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction (Mecanum only) ``` diff --git a/docs/uk/msg_docs/TrajectorySetpoint6dof.md b/docs/uk/msg_docs/TrajectorySetpoint6dof.md new file mode 100644 index 0000000000..f2629e19c4 --- /dev/null +++ b/docs/uk/msg_docs/TrajectorySetpoint6dof.md @@ -0,0 +1,23 @@ +# TrajectorySetpoint6dof (UORB message) + +Trajectory setpoint in NED frame +Input to position controller. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TrajectorySetpoint6dof.msg) + +```c +# Trajectory setpoint in NED frame +# Input to position controller. + +uint64 timestamp # time since system start (microseconds) + +# NED local world frame +float32[3] position # in meters +float32[3] velocity # in meters/second +float32[3] acceleration # in meters/second^2 +float32[3] jerk # in meters/second^3 (for logging only) + +float32[4] quaternion # unit quaternion +float32[3] angular_velocity # angular velocity in radians/second + +``` diff --git a/docs/uk/msg_docs/VehicleAttitudeSetpoint.md b/docs/uk/msg_docs/VehicleAttitudeSetpoint.md index 1be6e9f39b..9b6be02c9b 100644 --- a/docs/uk/msg_docs/VehicleAttitudeSetpoint.md +++ b/docs/uk/msg_docs/VehicleAttitudeSetpoint.md @@ -3,7 +3,7 @@ [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) ```c -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # time since system start (microseconds) @@ -16,10 +16,6 @@ float32[4] q_d # Desired quaternion for quaternion control # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] -bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) - -bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) - # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint ``` diff --git a/docs/uk/msg_docs/VehicleAttitudeSetpointV0.md b/docs/uk/msg_docs/VehicleAttitudeSetpointV0.md new file mode 100644 index 0000000000..6eb03e797c --- /dev/null +++ b/docs/uk/msg_docs/VehicleAttitudeSetpointV0.md @@ -0,0 +1,25 @@ +# VehicleAttitudeSetpointV0 (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 yaw_sp_move_rate # rad/s (commanded by user) + +# For quaternion-based attitude control +float32[4] q_d # Desired quaternion for quaternion control + +# For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. +# For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. +float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] + +bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) + +bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) + +# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint + +``` diff --git a/docs/uk/msg_docs/VehicleCommand.md b/docs/uk/msg_docs/VehicleCommand.md index dc85991022..00848d8e4b 100644 --- a/docs/uk/msg_docs/VehicleCommand.md +++ b/docs/uk/msg_docs/VehicleCommand.md @@ -11,127 +11,127 @@ Vehicle Command uORB повідомлення. Використовується uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start. -uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command -uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command -uint16 VEHICLE_CMD_CUSTOM_2 = 2 # test command -uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |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_PRECLAND = 23 # Attempt a precision landing -uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |Major Radius [m] |Minor Radius [m] |Velocity [m/s] |Orientation |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| -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_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_CONDITION_GATE = 4501 # Wait until passing a threshold |2D coord mode: 0: Orthogonal to planned route | Altitude mode: 0: Ignore altitude| Empty| Empty| Lat| Lon| Alt| -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 cycles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| 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_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value |Altitude| Frame of new altitude | Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1| Actuator 2| Actuator 3| Actuator 4| Actuator 5| Actuator 6| Index| -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 autonomous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |Ground speed [m/s] |Bitmask |Loiter radius [m] for planes |Yaw [deg] |Latitude |Longitude |Altitude | +uint16 VEHICLE_CMD_CUSTOM_0 = 0 # Test command. +uint16 VEHICLE_CMD_CUSTOM_1 = 1 # Test command. +uint16 VEHICLE_CMD_CUSTOM_2 = 2 # Test command. +uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |[s] (decimal) Hold time. (ignored by fixed wing, time to stay at MISSION for rotary wing)|[m] Acceptance radius (if the sphere with this radius is hit, the MISSION counts as reached)|0 to pass through the WP, if > 0 radius [m] to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.|Desired yaw angle at MISSION (rotary wing)|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time. |Unused|Unused|[m] Radius around MISSION. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns. |Turns|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for time. |[s] Seconds (decimal)|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand. |Unused (FW pitch from FW_TKO_PITCH_MIN)|Unused|Unused|[deg] [@range 0,360] Yaw angle in NED if yaw source available, ignored otherwise|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude AMSL| +uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing. +uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |[m] Radius|[m/s] Velocity|[@enum ORBIT_YAW_BEHAVIOUR] Yaw behaviour|Unused|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |[m] Major radius|[m] Minor radius|[m/s] Velocity|Orientation|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| +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|Unused|[deg] [@range 0, 360] Yaw angle at goal, in compass degrees|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|Unused|Unused|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. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min AMSL - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time. |[s] Delay (decimal, -1 to enable time-of-day fields)|[h] hour (24h format, UTC, -1 to ignore)|minute (24h format, UTC, -1 to ignore)|second (24h format, UTC)|Unused|Unused|Unused| +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.|Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |[s] Delay (decimal seconds)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached.|Descent / Ascend rate (m/s)|Unused|Unused|Unused|Unused|Unused|Finish Altitude| +uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance [m]|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |[deg] [@range 0,360] Target angle. 0 is north|[deg/s] Speed during yaw change|[@range -1,1] Direction: negative: counter clockwise, positive: clockwise |[ 1,0] Relative offset or absolute angle|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_GATE = 4501 # Wait until passing a threshold. |2D coord mode: 0: Orthogonal to planned route|Altitude mode: 0: Ignore altitude|Unused|Unused|Lat|Lon|Alt| +uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE|Unused|Unused|Unused|Unused|Unused|Unused| +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|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |[@enum SPEED_TYPE] Speed type (0=Airspeed, 1=Ground Speed)|Speed (m/s, -1 indicates no change)|[%] Throttle ( Percent, -1 indicates no change)|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|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|Unused|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cycles with a desired period. |Relay number|Cycle count|[s] Cycle time (decimal seconds)|Unused|Unused|Unused|Unused| +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|[us] PWM rate (1000 to 2000 typical)|Cycle count|[s] Cycle time|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately. |Flight termination activated if > 0.5|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value. |Altitude|Frame of new altitude|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1|Actuator 2|Actuator 3|Actuator 4|Actuator 5|Actuator 6|Index| +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. |Unused|Unused|Unused|Unused|Latitude|Longitude|Unused| +uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonomous landing. |[m] Altitude|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |[m/s] Ground speed|Bitmask|[m] Loiter radius for planes|[deg] Yaw|Latitude|Longitude|Altitude| uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193 -uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint| -uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| +uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Pitch offset from next waypoint|Roll offset from next waypoint|Yaw offset from next waypoint| +uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)|Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw|Transmission mode: 0: video stream, >0: single images every n seconds (decimal seconds)|Recording: 0: disabled, 1: enabled compressed, 2: enabled raw|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| uint16 VEHICLE_CMD_DO_DIGICAM_CONTROL=203 -uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # motor test command |Instance (1, ...)| throttle type| throttle| timeout [s]| Motor count | Test order| Empty| -uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # 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_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See mavlink spec MAV_CMD_PREFLIGHT_CALIBRATION -uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration -uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| -uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started -uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty| -uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode |MAV_STANDARD_MODE| -uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal +uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount. |[@enum MAV_MOUNT_MODE] Mount operation mode|Stabilize roll? (1 = yes, 0 = no)|Stabilize pitch? (1 = yes, 0 = no)|stabilize yaw? (1 = yes, 0 = no)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount. |[deg] Pitch or lat, depending on mount mode.|[deg] Roll or lon depending on mount mode|[deg]/[m] Yaw or alt depending on mount mode|Unused|Unused|Unused|[@enum MAV_MOUNT_MODE]| +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence. |enable? (0=disable, 1=enable)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute. |action [@enum PARACHUTE_ACTION] (0=disable, 1=enable, 2=release, for some systems see [@enum PARACHUTE_ACTION], not in general message set.)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # Motor test command. |Instance (@range 1, )|throttle type|throttle|timeout [s]|Motor count|Test order|Unused| +uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight. |inverted (0=normal, 1=inverted)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper. +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight. |[m] Camera trigger distance|Shutter integration time (ms)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)|q2 - quaternion param #2, x (0 in null-rotation)|q3 - quaternion param #3, y (0 in null-rotation)|q4 - quaternion param #4, z (0 in null-rotation)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min(AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See MAVLink spec MAV_CMD_PREFLIGHT_CALIBRATION. +uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# Param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration. +uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow|X axis offset (or generic dimension 1), in the sensor's raw units|Y axis offset (or generic dimension 2), in the sensor's raw units|Z axis offset (or generic dimension 3), in the sensor's raw units|Generic dimension 4, in the sensor's raw units|Generic dimension 5, in the sensor's raw units|Generic dimension 6, in the sensor's raw units| +uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started. +uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.|0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Camera minimum trigger interval|Number of positions|Roll|Pitch|Unused| +uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode. |MAV_STANDARD_MODE| +uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal. -uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| -uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command|value [-1,1]|timeout [s]|Empty|Empty|output function| -uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|configuration|Empty|Empty|Empty|output function| -uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm -uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. -uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes -uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| -uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message -uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| -uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.) -uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom +uint16 VEHICLE_CMD_MISSION_START = 300 # Start running a mission. |first_item: the first mission item to run|last_item: the last mission item to run (after this item is run, the mission ends)| +uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command. |[@range -1,1] value|[s] timeout|Unused|Unused|output function| +uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command. |configuration|Unused|Unused|Unused|output function| +uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component. |1 to arm, 0 to disarm. +uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. +uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes. +uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing. |0:Spektrum|0:Spektrum DSM2, 1:Spektrum DSMX| +uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message. +uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities|Reserved (all remaining params)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)| +uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). +uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control -uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. -uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system -uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. -uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. -uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data -uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data -uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link -uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition -uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization -uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan -uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment -uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. -uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. +uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. +uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. +uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. +uint16 VEHICLE_CMD_LOGGING_START = 2510 # Start streaming ULog data. +uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # Stop streaming ULog data. +uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # Control starting/stopping transmitting data over the high latency link. +uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition. +uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization. +uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan. +uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment. +uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. +uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. -uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # external reset of estimator global position when deadreckoning +uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # External reset of estimator global position when dead reckoning. uint16 VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE = 43004 -# PX4 vehicle commands (beyond 16 bit mavlink commands) -uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX) -uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude| -uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty| +# PX4 vehicle commands (beyond 16 bit MAVLink commands). +uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # Start of PX4 internal only vehicle commands (> UINT16_MAX). +uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Unused|Unused|Unused|Unused|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude (AMSL from GNSS, positive above ground)| +uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Unused|Unused|Unused|Unused|Unused|Unused| -uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization | -uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | -uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt | -uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # +uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization. +uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt. +uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # -uint8 VEHICLE_ROI_NONE = 0 # No region of interest | -uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | -uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | -uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | -uint8 VEHICLE_ROI_TARGET = 4 # Point toward target +uint8 VEHICLE_ROI_NONE = 0 # No region of interest. +uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION. +uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION. +uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location. +uint8 VEHICLE_ROI_TARGET = 4 # Point toward target. uint8 VEHICLE_ROI_ENUM_END = 5 uint8 PARACHUTE_ACTION_DISABLE = 0 @@ -163,13 +163,13 @@ uint8 FAILURE_TYPE_SLOW = 5 uint8 FAILURE_TYPE_DELAYED = 6 uint8 FAILURE_TYPE_INTERMITTENT = 7 -# used as param1 in DO_CHANGE_SPEED command +# Used as param1 in DO_CHANGE_SPEED command. uint8 SPEED_TYPE_AIRSPEED = 0 uint8 SPEED_TYPE_GROUNDSPEED = 1 uint8 SPEED_TYPE_CLIMB_SPEED = 2 uint8 SPEED_TYPE_DESCEND_SPEED = 3 -# used as param3 in CMD_DO_ORBIT +# Used as param3 in CMD_DO_ORBIT. uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0 uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 @@ -177,29 +177,29 @@ uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 -# used as param1 in ARM_DISARM command +# Used as param1 in ARM_DISARM command. int8 ARMING_ACTION_DISARM = 0 int8 ARMING_ACTION_ARM = 1 -# param2 in VEHICLE_CMD_DO_GRIPPER +# param2 in VEHICLE_CMD_DO_GRIPPER. uint8 GRIPPER_ACTION_RELEASE = 0 uint8 GRIPPER_ACTION_GRAB = 1 uint8 ORB_QUEUE_LENGTH = 8 -float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. -uint32 command # Command ID -uint8 target_system # System which should execute the command -uint8 target_component # Component which should execute the command, 0 for all components -uint8 source_system # System sending the command -uint16 source_component # Component / mode executor sending the command -uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. +uint32 command # Command ID. +uint8 target_system # System which should execute the command. +uint8 target_component # Component which should execute the command, 0 for all components. +uint8 source_system # System sending the command. +uint16 source_component # Component / mode executor sending the command. +uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command). bool from_external uint16 COMPONENT_MODE_EXECUTOR_START = 1000 diff --git a/docs/uk/msg_docs/index.md b/docs/uk/msg_docs/index.md index 722c5f9322..c55bf33e24 100644 --- a/docs/uk/msg_docs/index.md +++ b/docs/uk/msg_docs/index.md @@ -15,10 +15,18 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message +- [AirspeedValidated](AirspeedValidated.md) - [ArmingCheckReply](ArmingCheckReply.md) - [ArmingCheckRequest](ArmingCheckRequest.md) - [BatteryStatus](BatteryStatus.md) - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors +- [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message + Used by the fw_lateral_longitudinal_control module + At least one of course, airspeed_direction, or lateral_acceleration must be finite. +- [FixedWingLongitudinalSetpoint](FixedWingLongitudinalSetpoint.md) — Fixed Wing Longitudinal Setpoint message + Used by the fw_lateral_longitudinal_control module + If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. + If both altitude and height_rate are NAN, the controller maintains the current altitude. - [GotoSetpoint](GotoSetpoint.md) — Position and (optional) heading setpoints with corresponding speed constraints Setpoints are intended as inputs to position and heading smoothers, respectively Setpoints do not need to be kinematically consistent @@ -26,6 +34,11 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m Unset optional setpoints are not controlled Unset optional constraints default to vehicle specifications - [HomePosition](HomePosition.md) — GPS home position in WGS84 coordinates. +- [LateralControlConfiguration](LateralControlConfiguration.md) — Fixed Wing Lateral Control Configuration message + Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. +- [LongitudinalControlConfiguration](LongitudinalControlConfiguration.md) — Fixed Wing Longitudinal Control Configuration message + Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages + and configure the resultant setpoints. - [ManualControlSetpoint](ManualControlSetpoint.md) - [ModeCompleted](ModeCompleted.md) — Mode completion result, published by an active mode. Можливі значення nav_state визначені в повідомленні VehicleStatus. @@ -76,8 +89,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [Airspeed](Airspeed.md) -- [AirspeedValidated](AirspeedValidated.md) - - [AirspeedWind](AirspeedWind.md) - [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) @@ -92,7 +103,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [CanInterfaceStatus](CanInterfaceStatus.md) -- [CellularStatus](CellularStatus.md) +- [CellularStatus](CellularStatus.md) — Cellular status - [CollisionConstraints](CollisionConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -161,6 +172,14 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [FigureEightStatus](FigureEightStatus.md) +- [FixedWingLateralGuidanceStatus](FixedWingLateralGuidanceStatus.md) — Fixed Wing Lateral Guidance Status message + Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +- [FixedWingLateralStatus](FixedWingLateralStatus.md) — Fixed Wing Lateral Status message + Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +- [FixedWingRunwayControl](FixedWingRunwayControl.md) — Auxiliary control fields for fixed-wing runway takeoff/landing + - [FlightPhaseEstimation](FlightPhaseEstimation.md) - [FollowTarget](FollowTarget.md) @@ -267,8 +286,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md) -- [NpfgStatus](NpfgStatus.md) - - [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor. - [OffboardControlMode](OffboardControlMode.md) — Off-board control mode @@ -340,6 +357,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverAttitudeStatus](RoverAttitudeStatus.md) +- [RoverPositionSetpoint](RoverPositionSetpoint.md) + - [RoverRateSetpoint](RoverRateSetpoint.md) - [RoverRateStatus](RoverRateStatus.md) @@ -348,6 +367,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) +- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) + - [RoverVelocityStatus](RoverVelocityStatus.md) - [Rpm](Rpm.md) @@ -415,6 +436,9 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [TimesyncStatus](TimesyncStatus.md) +- [TrajectorySetpoint6dof](TrajectorySetpoint6dof.md) — Trajectory setpoint in NED frame + Input to position controller. + - [TransponderReport](TransponderReport.md) - [TuneControl](TuneControl.md) — This message is used to control the tunes, when the tune_id is set to CUSTOM @@ -467,4 +491,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [YawEstimatorStatus](YawEstimatorStatus.md) +- [AirspeedValidatedV0](AirspeedValidatedV0.md) + +- [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md) + - [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander \ No newline at end of file diff --git a/docs/uk/ros2/px4_ros2_control_interface.md b/docs/uk/ros2/px4_ros2_control_interface.md index 9c64317303..471d316906 100644 --- a/docs/uk/ros2/px4_ros2_control_interface.md +++ b/docs/uk/ros2/px4_ros2_control_interface.md @@ -346,6 +346,7 @@ private: Наступні розділи надають список підтримуваних типів установок: - GotoSetpointType: Плавне позиціонування та (за бажанням) керування курсом +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - DirectActuatorsSetpointType: Пряме керування моторами та установками сервоприводів польотних поверхонь :::tip @@ -360,7 +361,7 @@ The other setpoint types are currently experimental, and can be found in: [px4_r Цей тип установки наразі підтримується лише для багтрикоптерів. ::: -Плавне керування позицією та (за бажанням) керуванням установками курсу за допомогою типу установки px4_ros2::GotoSetpointType. +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. Тип установки транслюється до плавних позиційних та курсових вирівнювачів на основі FMU, сформульованих з оптимальним за часом, максимальною швидкістю зміни прискорення, з обмеженнями швидкості та прискорення. Найбільш тривіальне використання полягає в простому введенні 3D-позиції в метод оновлення: @@ -405,6 +406,137 @@ _goto_setpoint->update( max_heading_rate_rad_s); ``` +#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) + + + +:::info +This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. +::: + +Use the [`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html) to directly control the lateral and longitudinal dynamics of a fixed-wing vehicle — that is, side-to-side motion (turning/banking) and forward/vertical motion (speeding up and climbing/descending), respectively. +This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../modules/modules_controller.md#fw-lat-lon-control), which decouples lateral and longitudinal inputs while ensuring that vehicle limits are respected. + +To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: + +1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. + If both are set to `NAN`, the vehicle will maintain its current altitude. +2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. + +For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). + +##### Основне використання + +This type has a number of update methods, each allowing you to specify an increasing number of setpoints. + +The simplest method is `updateWithAltitude()`, which allows you to specify a `course` and `altitude` target setpoint: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, course); +``` + +PX4 uses the setpoints to compute the _roll angle_, _pitch angle_ and _throttle_ setpoints that are sent to lower level controllers. +Note that the commanded flight is expected to be relatively gentle/unaggressive when using this method. +This is done as follows: + +- Lateral control output: + + course setpoint (set by user) → airspeed direction (heading) setpoint → lateral acceleration setpoint → roll angle setpoint. + +- Longitudinal control output: + + altitude setpoint (set by user) → height rate setpoint → pitch angle setpoint and throttle settings. + +The `updateWithHeightRate()` method allows you to set a target `course` and `height_rate` (this is useful if the speed of ascent or descent matters, or needs to be dynamically controlled): + +```cpp +const float height_rate = 2.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithHeightRate(height_rate, course); +``` + +The `updateWithAltitude()` and `updateWithHeightRate()` methods allow you to additionally control the equivalent airspeed or lateral acceleration by specifying them as the third and fourth arguments, respectively: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +const float equivalent_aspd = 15.F; // m/s +const float lateral_acceleration = 2.F; // FRD, used as feedforward + +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, + course, + equivalent_aspd, + lateral_acceleration); +``` + +The equivalent airspeed and lateral acceleration arguments are defined as `std::optional`, so you can omit any of them by passing `std::nullopt`. + +:::tip +If both lateral acceleration and course setpoints are provided, the lateral acceleration setpoint will be used as feedforward. +::: + +##### Full Control Using the Setpoint Struct + +For full flexibility, you can create and pass a [`FwLateralLongitudinalSetpoint`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwLateralLongitudinalSetpoint.html) struct. +Each field is templated with `std::optional`. + +:::tip +If both course and airspeed direction are set: airspeed direction takes precedence, course is not controlled. +Lateral acceleration is treated as feedforward if either course or airspeed direction are also finite. +If both altitude and height rate are set: height rate takes precedence, altitude is not controlled. +::: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withCourse(0.F); +// setpoint_s.withAirspeedDirection(0.2F); // uncontrolled +setpoint_s.withLateralAcceleration(2.F); // feedforward +//setpoint_s.withAltitude(500.F); // uncontrolled +setpoint_s.withHeightRate(2.F); +setpoint_s.withEquivalentAirspeed(15.F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s); +``` + +The diagram below illustrates the interaction between the `FwLateralLongitudinalSetpointType` and PX4 when all inputs are set. + +![FW ROS Interaction](../../assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg) + +##### Advanced Configuration (Optional) + +You can also pass a [`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) struct along with the setpoint to override default controller settings and constraints such as pitch limits, throttle limits, and target sink/climb rates. +This is intended for advanced users: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withAirspeedDirection(0.F); +setpoint_s.withLateralAcceleration(2.F); // feedforward +setpoint_s.withAltitude(500.F); +setpoint_s.withEquivalentAirspeed(15.F); + +px4_ros2::FwControlConfiguration config_s; + +config_s.withTargetClimbRate(3.F); +config_s.withMaxAcceleration(5.F); +config_s.withThrottleLimits(0.4F, 0.6F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); +``` + +All configuration fields are defined as `std::optional`. +Unset values will default to the PX4 configuration. +See [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) and [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md) for more information on configuration options. + +:::info +For safety, PX4 automatically limits configuration values to stay within the vehicle’s constraints. +For example, throttle overrides are clamped to remain between [`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) +and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). +::: + #### Безпосереднє значення параметра Control (DirectActuatorsSetpointType) Клапани можна безпосередньо керувати, використовуючи тип встановлення px4_ros2::DirectActuatorsSetpointType. @@ -416,11 +548,55 @@ _goto_setpoint->update( Якщо ви хочете керувати клапаном, який не контролює рух транспортного засобу, але, наприклад, сервопривід навантаження, подивіться нижче. ::: +### Controlling a VTOL + + + +To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: + +- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). + +As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. + +If you would like to command a VTOL transition in your external mode, you need to use the [VTOL API](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1VTOL.html). The VTOL API provides the functionality to command a transition and query the current state of the vehicle. + +Use this API with caution! +Commanding transitions externally makes the user partially responsible for ensuring smooth and safe behavior, unlike onboard transitions (e.g. via RC switch) where PX4 handles the full process: + +1. Ensure that both the `TrajectorySetpointType` and the `FwLateralLongitudinalSetpointType` are available to your mode. +2. Create an instance of `px4_ros2::VTOL` in the constructor of your mode. +3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. +4. During transition, send the following combination of setpoints: + + ```cpp + // Assuming the instance of the px4_ros2::VTOL object is called vtol + + // Send TrajectorySetpointType as follows: + Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); + Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; + + _trajectory_setpoint->update(velocity_sp, acceleration_sp); + + // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired + + float course_sp = 0.F; // North + + _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) + ``` + + This will ensure that the transition is handled properly within PX4. + You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + +To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. + +See [this external flight mode implementation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol) for a practical example on how to use this API. + ### Керування незалежним клапаном/сервоприводом Якщо ви хочете керувати незалежним клапаном (сервоприводом), дотримуйтесь цих кроків: -1. Налаштуйте вивід +1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). 2. Створіть екземпляр px4_ros2::PeripheralActuatorControls у конструкторі вашого режиму. 3. Викличте метод set(), щоб керувати клапаном(-ами). Це може бути зроблено незалежно від будь-яких активних встановлень. @@ -432,6 +608,7 @@ _goto_setpoint->update( - [OdometryGlobalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryGlobalPosition.html): Global position - [OdometryLocalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryLocalPosition.html): Local position, velocity, acceleration, and heading - [OdometryAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAttitude.html): Vehicle attitude +- [OdometryAirspeed](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAirspeed.html): Airspeed Наприклад, ви можете надати запит на поточну позицію автомобіля наступним чином: diff --git a/docs/uk/sim_gazebo_gz/index.md b/docs/uk/sim_gazebo_gz/index.md index 74cf4c66c4..8b9c17d00f 100644 --- a/docs/uk/sim_gazebo_gz/index.md +++ b/docs/uk/sim_gazebo_gz/index.md @@ -396,6 +396,11 @@ As long as the world file and the model file are in the Gazebo search path (`GZ_ However, `make px4_sitl gz__` won't work with them. ::: +## Extending Gazebo with Plugins + +World, vehicle (model), and sensor behaviour can be customised using plugins. +For more information see [Gazebo Plugins](../sim_gazebo_gz/plugins.md). + ## Симуляція кількох рухомих засобів Симуляція кількох засобів підтримується на комп'ютерах з Linux. diff --git a/docs/uk/sim_gazebo_gz/plugins.md b/docs/uk/sim_gazebo_gz/plugins.md new file mode 100644 index 0000000000..9723f44177 --- /dev/null +++ b/docs/uk/sim_gazebo_gz/plugins.md @@ -0,0 +1,92 @@ +# Gazebo Plugins + +Gazebo plugins extend the simulator with custom functionality not provided by default. They can be attached to different entity types and allow you to add new sensors, modify world physics, or interact with the simulation environment. + +## Plugin Types + +Plugins can be attached to these entity types: + +- **World** - Global simulation behavior +- **Model** - Specific model functionality +- **Sensor** - Custom sensor implementations +- **Actor** - Dynamic entity behavior + +## Supported Plugins + +PX4 currently supports these plugins: + +- [OpticalFlowSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/optical_flow): Provides optical flow sensor simulation using OpenCV-based flow calculation. +- [GstCameraSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/gstreamer): Streams camera feeds via UDP (RTP/H.264) or RTMP with optional NVIDIA CUDA hardware acceleration. +- [MovingPlatformController](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/moving_platform_controller): Controls moving platforms (ships, trucks, etc.) for takeoff and landing scenarios. + Includes configurable velocity, heading, and random fluctuations. + +## Plugin Registration + +Plugins must be registered in the [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) file to be available in your world: + +```xml + + + + + + + + + + +``` + +## Creating Custom Plugins + +When developing new plugins: + +1. **Follow the plugin architecture** - Implement desired interfaces. + + You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. + The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). + +2. **Register your plugin** - Add it to [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) for discovery. + +3. **Use the custom namespace** - Follow the pattern `custom::YourPluginName`. + +### Example Plugin Structure + +```cpp +class YourCustomSystem : + public gz::sim::System, + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemPostUpdate +{ +public: + void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; + void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; +}; + +// Plugin registration +GZ_ADD_PLUGIN(YourCustomSystem, gz::sim::System, + YourCustomSystem::ISystemPreUpdate, + YourCustomSystem::ISystemPostUpdate) +GZ_ADD_PLUGIN_ALIAS(YourCustomSystem, "custom::YourCustomSystem") +``` + +## Enabling a Plugin + +For world plugins all you need to do is [register the plugin](#plugin-registration) (add it to the `server.config`). +It will then be available to all worlds and vehicles. + +The process for adding vehicle model/sensor plugins is not documented. +This can tracked through [PX4-Autopilot#2493](https://github.com/PX4/PX4-Autopilot/issues/24939). + +## Resources + +- **PX4 Plugins**: [Repository source code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins) +- **Official Gazebo Documentation**: [System Plugins Guide](https://gazebosim.org/api/sim/9/createsystemplugins.html) +- **Server Configuration**: [Configuration Reference](https://gazebosim.org/api/sim/9/server_config.html) +- **PX4 Gazebo-classic Plugins**: [PX4 Gazebo Classic Plugins](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/main/src) + +:::info +Plugins for modern Gazebo are still evolving. The plugin system differs from Gazebo Classic. +::: diff --git a/docs/uk/telemetry/crsf_telemetry.md b/docs/uk/telemetry/crsf_telemetry.md index 6ca4bf6150..740a621a35 100644 --- a/docs/uk/telemetry/crsf_telemetry.md +++ b/docs/uk/telemetry/crsf_telemetry.md @@ -71,7 +71,7 @@ For ExpressLRS receivers wire to the flight controller UART as shown below (wiri ### Конфігурація прошивки/збірка Підтримка телеметрії CRSF не включена в жодне ПЗ PX4 за замовчуванням. -To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver.md#crsf-rc) and removes [rc_input](../modules/modules_driver.md#rc-input). +To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver_radio_control.md#crsf-rc) and removes [rc_input](../modules/modules_driver_radio_control.md#rc-input). Кроки наступні: diff --git a/docs/uk/tutorials/linux_sbus.md b/docs/uk/tutorials/linux_sbus.md index d6152de51b..42bf4db62a 100644 --- a/docs/uk/tutorials/linux_sbus.md +++ b/docs/uk/tutorials/linux_sbus.md @@ -10,9 +10,7 @@ For an S.Bus receiver (or encoder - e.g. from Futaba, RadioLink, etc.) you will Then [Start the PX4 RC Driver](#start_driver) on the device, as shown below. - - -## Запуск драйвера +## Starting the Driver {#start_driver} To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): @@ -20,11 +18,9 @@ To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): rc_input start -d /dev/ttyS2 ``` -For other driver usage information see: [rc_input](../modules/modules_driver.md#rc-input). +For other driver usage information see: [rc_input](../modules/modules_driver_radio_control.md#rc-input). - - -## Схема інвертування сигналу (лише для S.Bus) +## Signal Inverter Circuit (S.Bus only) {#signal_inverter_circuit} S.Bus is an _inverted_ UART communication signal. From 5c6645e6ef740410a8eca7e636031dcc20a021d5 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Mon, 2 Jun 2025 07:43:39 +1000 Subject: [PATCH 079/130] New Crowdin translations - zh-CN (#24950) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 20 +- docs/zh/config/safety.md | 19 +- docs/zh/contribute/docs.md | 16 +- docs/zh/flight_modes_fw/land.md | 11 +- docs/zh/flight_modes_fw/takeoff.md | 42 +-- docs/zh/frames_plane/reptile_dragon_2.md | 2 +- docs/zh/middleware/uxrce_dds.md | 4 + docs/zh/modules/modules_controller.md | 32 ++- docs/zh/modules/modules_driver.md | 4 +- docs/zh/modules/modules_system.md | 1 + docs/zh/msg_docs/AirspeedValidated.md | 26 +- docs/zh/msg_docs/AirspeedValidatedV0.md | 25 ++ docs/zh/msg_docs/CellularStatus.md | 64 +++-- .../FixedWingLateralGuidanceStatus.md | 23 ++ docs/zh/msg_docs/FixedWingLateralSetpoint.md | 22 ++ docs/zh/msg_docs/FixedWingLateralStatus.md | 17 ++ .../msg_docs/FixedWingLongitudinalSetpoint.md | 26 ++ docs/zh/msg_docs/FixedWingRunwayControl.md | 19 ++ .../msg_docs/LateralControlConfiguration.md | 18 ++ .../LongitudinalControlConfiguration.md | 28 ++ docs/zh/msg_docs/PurePursuitStatus.md | 2 - docs/zh/msg_docs/RateCtrlStatus.md | 1 - docs/zh/msg_docs/RoverAttitudeSetpoint.md | 2 - docs/zh/msg_docs/RoverAttitudeStatus.md | 2 - docs/zh/msg_docs/RoverPositionSetpoint.md | 15 + docs/zh/msg_docs/RoverRateSetpoint.md | 2 - docs/zh/msg_docs/RoverRateStatus.md | 2 - docs/zh/msg_docs/RoverSteeringSetpoint.md | 5 +- docs/zh/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/zh/msg_docs/RoverVelocitySetpoint.md | 12 + docs/zh/msg_docs/RoverVelocityStatus.md | 10 +- docs/zh/msg_docs/TrajectorySetpoint6dof.md | 23 ++ docs/zh/msg_docs/VehicleAttitudeSetpoint.md | 6 +- docs/zh/msg_docs/VehicleAttitudeSetpointV0.md | 25 ++ docs/zh/msg_docs/VehicleCommand.md | 256 +++++++++--------- docs/zh/msg_docs/index.md | 38 ++- docs/zh/ros2/px4_ros2_control_interface.md | 181 ++++++++++++- docs/zh/sim_gazebo_gz/index.md | 5 + docs/zh/sim_gazebo_gz/plugins.md | 92 +++++++ docs/zh/telemetry/crsf_telemetry.md | 2 +- docs/zh/tutorials/linux_sbus.md | 10 +- 41 files changed, 864 insertions(+), 252 deletions(-) create mode 100644 docs/zh/msg_docs/AirspeedValidatedV0.md create mode 100644 docs/zh/msg_docs/FixedWingLateralGuidanceStatus.md create mode 100644 docs/zh/msg_docs/FixedWingLateralSetpoint.md create mode 100644 docs/zh/msg_docs/FixedWingLateralStatus.md create mode 100644 docs/zh/msg_docs/FixedWingLongitudinalSetpoint.md create mode 100644 docs/zh/msg_docs/FixedWingRunwayControl.md create mode 100644 docs/zh/msg_docs/LateralControlConfiguration.md create mode 100644 docs/zh/msg_docs/LongitudinalControlConfiguration.md create mode 100644 docs/zh/msg_docs/RoverPositionSetpoint.md create mode 100644 docs/zh/msg_docs/RoverVelocitySetpoint.md create mode 100644 docs/zh/msg_docs/TrajectorySetpoint6dof.md create mode 100644 docs/zh/msg_docs/VehicleAttitudeSetpointV0.md create mode 100644 docs/zh/sim_gazebo_gz/plugins.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index 0321a017bc..fea7e0aed3 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -459,6 +459,7 @@ - [Vehicles](sim_gazebo_gz/vehicles.md) - [Advanced Lift Drag Tool](sim_gazebo_gz/tools_avl_automation.md) - [Worlds](sim_gazebo_gz/worlds.md) + - [Plugins](sim_gazebo_gz/plugins.md) - [Gazebo Models Repository](sim_gazebo_gz/gazebo_models.md) - [Multi-Vehicle Sim](sim_gazebo_gz/multi_vehicle_simulation.md) - [Gazebo Classic Simulation](sim_gazebo_classic/index.md) @@ -491,12 +492,17 @@ - [Versioned](msg_docs/versioned_messages.md) - [ActuatorMotors](msg_docs/ActuatorMotors.md) - [ActuatorServos](msg_docs/ActuatorServos.md) + - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [ArmingCheckReply](msg_docs/ArmingCheckReply.md) - [ArmingCheckRequest](msg_docs/ArmingCheckRequest.md) - [BatteryStatus](msg_docs/BatteryStatus.md) - [ConfigOverrides](msg_docs/ConfigOverrides.md) + - [FixedWingLateralSetpoint](msg_docs/FixedWingLateralSetpoint.md) + - [FixedWingLongitudinalSetpoint](msg_docs/FixedWingLongitudinalSetpoint.md) - [GotoSetpoint](msg_docs/GotoSetpoint.md) - [HomePosition](msg_docs/HomePosition.md) + - [LateralControlConfiguration](msg_docs/LateralControlConfiguration.md) + - [LongitudinalControlConfiguration](msg_docs/LongitudinalControlConfiguration.md) - [ManualControlSetpoint](msg_docs/ManualControlSetpoint.md) - [ModeCompleted](msg_docs/ModeCompleted.md) - [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md) @@ -525,10 +531,8 @@ - [ActuatorTest](msg_docs/ActuatorTest.md) - [AdcReport](msg_docs/AdcReport.md) - [Airspeed](msg_docs/Airspeed.md) - - [AirspeedValidated](msg_docs/AirspeedValidated.md) - [AirspeedWind](msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](msg_docs/AutotuneAttitudeControlStatus.md) - - [Buffer128](msg_docs/Buffer128.md) - [ButtonEvent](msg_docs/ButtonEvent.md) - [CameraCapture](msg_docs/CameraCapture.md) - [CameraStatus](msg_docs/CameraStatus.md) @@ -567,6 +571,9 @@ - [FailsafeFlags](msg_docs/FailsafeFlags.md) - [FailureDetectorStatus](msg_docs/FailureDetectorStatus.md) - [FigureEightStatus](msg_docs/FigureEightStatus.md) + - [FixedWingLateralGuidanceStatus](msg_docs/FixedWingLateralGuidanceStatus.md) + - [FixedWingLateralStatus](msg_docs/FixedWingLateralStatus.md) + - [FixedWingRunwayControl](msg_docs/FixedWingRunwayControl.md) - [FlightPhaseEstimation](msg_docs/FlightPhaseEstimation.md) - [FollowTarget](msg_docs/FollowTarget.md) - [FollowTargetEstimator](msg_docs/FollowTargetEstimator.md) @@ -619,7 +626,6 @@ - [NavigatorMissionItem](msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](msg_docs/NavigatorStatus.md) - [NormalizedUnsignedSetpoint](msg_docs/NormalizedUnsignedSetpoint.md) - - [NpfgStatus](msg_docs/NpfgStatus.md) - [ObstacleDistance](msg_docs/ObstacleDistance.md) - [OffboardControlMode](msg_docs/OffboardControlMode.md) - [OnboardComputerStatus](msg_docs/OnboardComputerStatus.md) @@ -655,13 +661,12 @@ - [RcParameterMap](msg_docs/RcParameterMap.md) - [RoverAttitudeSetpoint](msg_docs/RoverAttitudeSetpoint.md) - [RoverAttitudeStatus](msg_docs/RoverAttitudeStatus.md) - - [RoverMecanumGuidanceStatus](msg_docs/RoverMecanumGuidanceStatus.md) - - [RoverMecanumSetpoint](msg_docs/RoverMecanumSetpoint.md) - - [RoverMecanumStatus](msg_docs/RoverMecanumStatus.md) + - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) + - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) - [RoverVelocityStatus](msg_docs/RoverVelocityStatus.md) - [Rpm](msg_docs/Rpm.md) - [RtlStatus](msg_docs/RtlStatus.md) @@ -693,6 +698,7 @@ - [TelemetryStatus](msg_docs/TelemetryStatus.md) - [TiltrotorExtraControls](msg_docs/TiltrotorExtraControls.md) - [TimesyncStatus](msg_docs/TimesyncStatus.md) + - [TrajectorySetpoint6dof](msg_docs/TrajectorySetpoint6dof.md) - [TransponderReport](msg_docs/TransponderReport.md) - [TuneControl](msg_docs/TuneControl.md) - [UavcanParameterRequest](msg_docs/UavcanParameterRequest.md) @@ -716,6 +722,8 @@ - [WheelEncoders](msg_docs/WheelEncoders.md) - [Wind](msg_docs/Wind.md) - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) + - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) + - [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md) - [VehicleStatusV0](msg_docs/VehicleStatusV0.md) - [MAVLink通讯](middleware/mavlink.md) - [Adding Messages](mavlink/adding_messages.md) diff --git a/docs/zh/config/safety.md b/docs/zh/config/safety.md index d1c813c15a..b4d1fffa52 100644 --- a/docs/zh/config/safety.md +++ b/docs/zh/config/safety.md @@ -187,7 +187,24 @@ The following settings also apply, but are not displayed in the QGC UI. ## Position (GNSS) Loss Failsafe -The _Position Loss Failsafe_ is triggered if the quality of the PX4 global position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The _Position Loss Failsafe_ is triggered if the quality of the PX4 position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. +The sections below cover first the trigger and then the failsafe action taken by the controller. + +### Position Loss Failsafe Trigger + +There are basically two mechanisms in PX4 to trigger position failsafes: + +- A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. +- The estimated horizontal position accuracy exceeds a certain threshold. This check is only done on hovering systems (rotary wing vehicles or VTOLs in hover phase). + +The relevant parameters shown below. + +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [EKF2_NOAID_TOUT](../advanced_config/parameter_reference.md#EKF2_NOAID_TOUT) | Maximum inertial dead-reckoning time, so the time after the last data sample was received of any sensor that constrains the velocity drift [microseconds]. | +| [COM_POS_FS_EPH](../advanced_config/parameter_reference.md#COM_POS_FS_EPH) | Horizontal position error threshold for hovering vehicles (Multicopters and VTOLs in hover). Fixed-wing vehicles have this value set to infinity. | + +### Position Loss Failsafe Action The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): diff --git a/docs/zh/contribute/docs.md b/docs/zh/contribute/docs.md index 1bf93036f2..bf401d8858 100644 --- a/docs/zh/contribute/docs.md +++ b/docs/zh/contribute/docs.md @@ -181,11 +181,19 @@ Within the repository you created above: 5. Open previewed pages in your local editor: First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. - For example, on Windows command line you can enable VSCode as your default editor by entering: + For example, you can enable VSCode as your default editor by entering: - ```sh - set EDITOR=code - ``` + - Windows: + + ```sh + set EDITOR=code + ``` + + - Linux: + + ```sh + export EDITOR=code + ``` The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). diff --git a/docs/zh/flight_modes_fw/land.md b/docs/zh/flight_modes_fw/land.md index d16b68b25b..0a4220437d 100644 --- a/docs/zh/flight_modes_fw/land.md +++ b/docs/zh/flight_modes_fw/land.md @@ -41,11 +41,12 @@ The vehicle will flare if configured to do so (see [Flaring](../flight_modes_fw/ Land mode behaviour can be configured using the parameters below. -| 参数 | 描述 | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------- | -| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | -| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | -| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | +| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | +| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. | ## See Also diff --git a/docs/zh/flight_modes_fw/takeoff.md b/docs/zh/flight_modes_fw/takeoff.md index 900377d4c4..76f3f5efa9 100644 --- a/docs/zh/flight_modes_fw/takeoff.md +++ b/docs/zh/flight_modes_fw/takeoff.md @@ -43,13 +43,14 @@ Reaching the clearance altitude causes the vehicle to enter [Hold mode](../fligh Parameters that affect both catapult/hand-launch and runway takeoffs: -| 参数 | 描述 | -| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Minimum altitude setpoint above Home that the vehicle will climb to during takeoff. | -| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) | -| [FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | This is the minimum pitch angle setpoint during the climbout phase | -| [FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Maximum climb rate. | -| [FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Flaps setpoint during takeoff | +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Minimum altitude setpoint above Home that the vehicle will climb to during takeoff. | +| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) | +| [FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | This is the minimum pitch angle setpoint during the climbout phase | +| [FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Maximum climb rate. | +| [FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Flaps setpoint during takeoff | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_TKO_AIRSPD is below FW_AIRSPD_MIN. | :::info The vehicle always respects normal FW max/min throttle settings during takeoff ([FW_THR_MIN](../advanced_config/parameter_reference.md#FW_THR_MIN), [FW_THR_MAX](../advanced_config/parameter_reference.md#FW_THR_MAX)). @@ -101,26 +102,25 @@ The _runway takeoff mode_ has the following phases: :::info For a smooth takeoff, the runway wheel controller possibly needs to be tuned. -It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)) and an outer loop that calculates heading setpoints from course errors and can be tuned via [RWTO_NPFG_PERIOD](#RWTO_NPFG_PERIOD). +It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)). ::: ### Parameters (Runway Takeoff) Runway takeoff is affected by the following parameters: -| 参数 | 描述 | -| ----------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Enable runway takeoff | -| [FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Enable wheel controller | -| [RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Max throttle during runway takeoff | -| [RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Throttle ramp up time | -| [RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Airspeed threshold to start rotation (pitching up). If not configured by operator is set to 0.9\*FW_TKO_AIRSPD. | -| [RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation. | -| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Airspeed setpoint during the takeoff climbout phase (after rotation). If not configured by operator is set to FW_AIRSPD_MIN. | -| [RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Enable wheel controller nudging while on the runway | -| [FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | The wingspan of the vehicle. Used to prevent wingstrikes. | -| [FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | The height of the wings above ground (ground clearance). Used to prevent wingstrikes. | -| [RWTO_NPFG_PERIOD](../advanced_config/parameter_reference.md#RWTO_NPFG_PERIOD) | L1 period while steering on runway. Increase for less aggressive response to course errors. | +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Enable runway takeoff | +| [FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Enable wheel controller | +| [RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Max throttle during runway takeoff | +| [RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Throttle ramp up time | +| [RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Airspeed threshold to start rotation (pitching up). If not configured by operator is set to 0.9\*FW_TKO_AIRSPD. | +| [RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation. | +| [FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Airspeed setpoint during the takeoff climbout phase (after rotation). If not configured by operator is set to FW_AIRSPD_MIN. | +| [RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Enable wheel controller nudging while on the runway | +| [FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | The wingspan of the vehicle. Used to prevent wingstrikes. | +| [FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | The height of the wings above ground (ground clearance). Used to prevent wingstrikes. | ## See Also diff --git a/docs/zh/frames_plane/reptile_dragon_2.md b/docs/zh/frames_plane/reptile_dragon_2.md index 971a70f43e..11e4bc7ba7 100644 --- a/docs/zh/frames_plane/reptile_dragon_2.md +++ b/docs/zh/frames_plane/reptile_dragon_2.md @@ -325,7 +325,7 @@ Access to this cable can be accomplished by simply removing the rear hatch and u ## Firmware Build -You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. +You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver_radio_control.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default. These require some custom configuration to enable. diff --git a/docs/zh/middleware/uxrce_dds.md b/docs/zh/middleware/uxrce_dds.md index b05430ddcb..c7814ed3fb 100644 --- a/docs/zh/middleware/uxrce_dds.md +++ b/docs/zh/middleware/uxrce_dds.md @@ -435,9 +435,11 @@ publications: - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry + rate_limit: 150. - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus + rate_limit: 50. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint @@ -472,6 +474,8 @@ Each (`topic`,`type`) pairs defines: - `/fmu/out/` for topics that are _published_ by PX4. - `/fmu/in/` for topics that are _subscribed_ by PX4. 4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition. +5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2. + If left unspecified, the maximum publication rate limit is set to 100 Hz. `subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively. Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers. diff --git a/docs/zh/modules/modules_controller.md b/docs/zh/modules/modules_controller.md index 68d8bdd25f..6a949f7dd7 100644 --- a/docs/zh/modules/modules_controller.md +++ b/docs/zh/modules/modules_controller.md @@ -91,18 +91,18 @@ fw_att_control [arguments...] status print status info ``` -## fw_pos_control +## fw_lat_lon_control -Source: [modules/fw_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_pos_control) +Source: [modules/fw_lateral_longitudinal_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_lateral_longitudinal_control) ### 描述 -fw_pos_control is the fixed-wing position controller. +fw_lat_lon_control computes attitude and throttle setpoints from lateral and longitudinal control setpoints. -### Usage {#fw_pos_control_usage} +### Usage {#fw_lat_lon_control_usage} ``` -fw_pos_control [arguments...] +fw_lat_lon_control [arguments...] Commands: start [vtol] VTOL mode @@ -112,6 +112,28 @@ fw_pos_control [arguments...] status print status info ``` +## fw_mode_manager + +Source: [modules/fw_mode_manager](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_mode_manager) + +### 描述 + +This implements the setpoint generation for all PX4-internal fixed-wing modes, height-rate control and higher. +It takes the current mode state of the vehicle as input and outputs setpoints consumed by the fixed-wing +lateral-longitudinal controller and and controllers below that (attitude, rate). + +### Usage {#fw_mode_manager_usage} + +``` +fw_mode_manager [arguments...] + Commands: + start + + stop + + status print status info +``` + ## fw_rate_control Source: [modules/fw_rate_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_rate_control) diff --git a/docs/zh/modules/modules_driver.md b/docs/zh/modules/modules_driver.md index ae19d698dc..9ce039cab3 100644 --- a/docs/zh/modules/modules_driver.md +++ b/docs/zh/modules/modules_driver.md @@ -293,7 +293,9 @@ dshot [arguments...] start telemetry Enable Telemetry on a UART - UART device + -d UART device + values: + [-x] Swap RX/TX pins reverse Reverse motor direction [-m ] Motor index (1-based, default=all) diff --git a/docs/zh/modules/modules_system.md b/docs/zh/modules/modules_system.md index 3d3f6b2905..e27bab2a1e 100644 --- a/docs/zh/modules/modules_system.md +++ b/docs/zh/modules/modules_system.md @@ -318,6 +318,7 @@ i2c_launcher [arguments...] Commands: start -b Bus number + -t battery index for calibration values (1 or 3) stop diff --git a/docs/zh/msg_docs/AirspeedValidated.md b/docs/zh/msg_docs/AirspeedValidated.md index eef1300688..9034960626 100644 --- a/docs/zh/msg_docs/AirspeedValidated.md +++ b/docs/zh/msg_docs/AirspeedValidated.md @@ -1,21 +1,27 @@ # AirspeedValidated (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AirspeedValidated.msg) +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +uint32 MESSAGE_VERSION = 1 + uint64 timestamp # time since system start (microseconds) -float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid -float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid +float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +int8 airspeed_source # Source of currently published airspeed values +int8 DISABLED = -1 +int8 GROUND_MINUS_WIND = 0 +int8 SENSOR_1 = 1 +int8 SENSOR_2 = 2 +int8 SENSOR_3 = 3 +int8 SYNTHETIC = 4 + +# debug states float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid - -bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. - -int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid - +float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] float32 throttle_filtered # filtered fixed-wing throttle [-] float32 pitch_filtered # filtered pitch [rad] diff --git a/docs/zh/msg_docs/AirspeedValidatedV0.md b/docs/zh/msg_docs/AirspeedValidatedV0.md new file mode 100644 index 0000000000..8bca98a224 --- /dev/null +++ b/docs/zh/msg_docs/AirspeedValidatedV0.md @@ -0,0 +1,25 @@ +# AirspeedValidatedV0 (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/AirspeedValidatedV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid +float32 calibrated_airspeed_m_s # calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid +float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid + +float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid +float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid + +bool airspeed_sensor_measurement_valid # True if data from at least one airspeed sensor is declared valid. + +int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid + +float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] +float32 throttle_filtered # filtered fixed-wing throttle [-] +float32 pitch_filtered # filtered pitch [rad] + +``` diff --git a/docs/zh/msg_docs/CellularStatus.md b/docs/zh/msg_docs/CellularStatus.md index 4984dc9a6b..466a1272fe 100644 --- a/docs/zh/msg_docs/CellularStatus.md +++ b/docs/zh/msg_docs/CellularStatus.md @@ -1,35 +1,49 @@ # CellularStatus (UORB message) +Cellular status + +This is currently used only for logging cell status from MAVLink. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CellularStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Cellular status +# +# This is currently used only for logging cell status from MAVLink. -uint8 CELLULAR_STATUS_FLAG_UNKNOWN=0 # State unknown or not reportable -uint8 CELLULAR_STATUS_FLAG_FAILED=1 # velocity setpoint -uint8 CELLULAR_STATUS_FLAG_INITIALIZING=2 # Modem is being initialized -uint8 CELLULAR_STATUS_FLAG_LOCKED=3 # Modem is locked -uint8 CELLULAR_STATUS_FLAG_DISABLED=4 # Modem is not enabled and is powered down -uint8 CELLULAR_STATUS_FLAG_DISABLING=5 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLING=6 # Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state -uint8 CELLULAR_STATUS_FLAG_ENABLED=7 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint8 CELLULAR_STATUS_FLAG_SEARCHING=8 # Modem is searching for a network provider to register -uint8 CELLULAR_STATUS_FLAG_REGISTERED=9 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint8 CELLULAR_STATUS_FLAG_DISCONNECTING=10 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint8 CELLULAR_STATUS_FLAG_CONNECTING=11 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint8 CELLULAR_STATUS_FLAG_CONNECTED=12 # One or more packet data bearers is active and connected +uint64 timestamp # [us] Time since system start. -uint8 CELLULAR_NETWORK_FAILED_REASON_NONE=0 # No error -uint8 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN=1 # Error state is unknown -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING=2 # SIM is required for the modem but missing -uint8 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3 # SIM is available, but not usable for connection +uint16 status # [@enum STATUS_FLAG] Status bitmap. +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable. +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable. +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized. +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked. +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down. +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state. +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state. +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections. +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register. +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use. +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated. +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered. +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected. -uint16 status # Status bitmap 1: Roaming is active -uint8 failure_reason #Failure reason when status in in CELLUAR_STATUS_FAILED -uint8 type # Cellular network radio type 0: none 1: gsm 2: cdma 3: wcdma 4: lte -uint8 quality # Cellular network RSSI/RSRP in dBm, absolute value -uint16 mcc # Mobile country code. If unknown, set to: UINT16_MAX -uint16 mnc # Mobile network code. If unknown, set to: UINT16_MAX -uint16 lac # Location area code. If unknown, set to: 0 +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason. +uint8 FAILURE_REASON_NONE = 0 # No error. +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown. +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing. +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection. + +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type. +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE + +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value. +uint16 mcc # [@invalid UINT16_MAX] Mobile country code. +uint16 mnc # [@invalid UINT16_MAX] Mobile network code. +uint16 lac # [@invalid 0] Location area code. ``` diff --git a/docs/zh/msg_docs/FixedWingLateralGuidanceStatus.md b/docs/zh/msg_docs/FixedWingLateralGuidanceStatus.md new file mode 100644 index 0000000000..02dc50b410 --- /dev/null +++ b/docs/zh/msg_docs/FixedWingLateralGuidanceStatus.md @@ -0,0 +1,23 @@ +# FixedWingLateralGuidanceStatus (UORB message) + +Fixed Wing Lateral Guidance Status message +Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralGuidanceStatus.msg) + +```c +# Fixed Wing Lateral Guidance Status message +# Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +uint64 timestamp # time since system start (microseconds) + +float32 course_setpoint # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. Set by guidance law +float32 lateral_acceleration_ff # [m/s^2] [FRD] lateral acceleration demand only for maintaining curvature +float32 bearing_feas # [@range 0,1] bearing feasibility +float32 bearing_feas_on_track # [@range 0,1] on-track bearing feasibility +float32 signed_track_error # [m] signed track error +float32 track_error_bound # [m] track error bound +float32 adapted_period # [s] adapted period (if auto-tuning enabled) +uint8 wind_est_valid # [boolean] true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) + +``` diff --git a/docs/zh/msg_docs/FixedWingLateralSetpoint.md b/docs/zh/msg_docs/FixedWingLateralSetpoint.md new file mode 100644 index 0000000000..153167bb62 --- /dev/null +++ b/docs/zh/msg_docs/FixedWingLateralSetpoint.md @@ -0,0 +1,22 @@ +# FixedWingLateralSetpoint (UORB message) + +Fixed Wing Lateral Setpoint message +Used by the fw_lateral_longitudinal_control module +At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLateralSetpoint.msg) + +```c +# Fixed Wing Lateral Setpoint message +# Used by the fw_lateral_longitudinal_control module +# At least one of course, airspeed_direction, or lateral_acceleration must be finite. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. +float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. +float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. + +``` diff --git a/docs/zh/msg_docs/FixedWingLateralStatus.md b/docs/zh/msg_docs/FixedWingLateralStatus.md new file mode 100644 index 0000000000..9214d1e9e0 --- /dev/null +++ b/docs/zh/msg_docs/FixedWingLateralStatus.md @@ -0,0 +1,17 @@ +# FixedWingLateralStatus (UORB message) + +Fixed Wing Lateral Status message +Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralStatus.msg) + +```c +# Fixed Wing Lateral Status message +# Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_acceleration_setpoint # [m/s^2] [FRD] resultant lateral acceleration setpoint +float32 can_run_factor # [norm] [@range 0, 1] estimate of certainty of the correct functionality of the npfg roll setpoint + +``` diff --git a/docs/zh/msg_docs/FixedWingLongitudinalSetpoint.md b/docs/zh/msg_docs/FixedWingLongitudinalSetpoint.md new file mode 100644 index 0000000000..6b8fb29e5b --- /dev/null +++ b/docs/zh/msg_docs/FixedWingLongitudinalSetpoint.md @@ -0,0 +1,26 @@ +# FixedWingLongitudinalSetpoint (UORB message) + +Fixed Wing Longitudinal Setpoint message +Used by the fw_lateral_longitudinal_control module +If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +If both altitude and height_rate are NAN, the controller maintains the current altitude. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLongitudinalSetpoint.msg) + +```c +# Fixed Wing Longitudinal Setpoint message +# Used by the fw_lateral_longitudinal_control module +# If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. +# If both altitude and height_rate are NAN, the controller maintains the current altitude. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite +float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not controlled directly +float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used +float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller +float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller + +``` diff --git a/docs/zh/msg_docs/FixedWingRunwayControl.md b/docs/zh/msg_docs/FixedWingRunwayControl.md new file mode 100644 index 0000000000..9e9f5ff428 --- /dev/null +++ b/docs/zh/msg_docs/FixedWingRunwayControl.md @@ -0,0 +1,19 @@ +# FixedWingRunwayControl (UORB message) + +Auxiliary control fields for fixed-wing runway takeoff/landing + +Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingRunwayControl.msg) + +```c +# Auxiliary control fields for fixed-wing runway takeoff/landing + +# Passes information from the FixedWingModeManager to the FixedWingAttitudeController + +uint64 timestamp # [us] time since system start + +bool wheel_steering_enabled # Flag that enables the wheel steering. +float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. + +``` diff --git a/docs/zh/msg_docs/LateralControlConfiguration.md b/docs/zh/msg_docs/LateralControlConfiguration.md new file mode 100644 index 0000000000..b0a03a6378 --- /dev/null +++ b/docs/zh/msg_docs/LateralControlConfiguration.md @@ -0,0 +1,18 @@ +# LateralControlConfiguration (UORB message) + +Fixed Wing Lateral Control Configuration message +Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LateralControlConfiguration.msg) + +```c +# Fixed Wing Lateral Control Configuration message +# Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY + +``` diff --git a/docs/zh/msg_docs/LongitudinalControlConfiguration.md b/docs/zh/msg_docs/LongitudinalControlConfiguration.md new file mode 100644 index 0000000000..901d5c23bc --- /dev/null +++ b/docs/zh/msg_docs/LongitudinalControlConfiguration.md @@ -0,0 +1,28 @@ +# LongitudinalControlConfiguration (UORB message) + +Fixed Wing Longitudinal Control Configuration message +Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +and configure the resultant setpoints. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LongitudinalControlConfiguration.msg) + +```c +# Fixed Wing Longitudinal Control Configuration message +# Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages +# and configure the resultant setpoints. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 pitch_min # [rad][@range -pi, pi] defaults to FW_P_LIM_MIN if NAN. +float32 pitch_max # [rad][@range -pi, pi] defaults to FW_P_LIM_MAX if NAN. +float32 throttle_min # [norm] [@range 0,1] deaults to FW_THR_MIN if NAN. +float32 throttle_max # [norm] [@range 0,1] defaults to FW_THR_MAX if NAN. +float32 climb_rate_target # [m/s] target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. +float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only +bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking +bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller + +``` diff --git a/docs/zh/msg_docs/PurePursuitStatus.md b/docs/zh/msg_docs/PurePursuitStatus.md index 76ae5524f0..1685af32d1 100644 --- a/docs/zh/msg_docs/PurePursuitStatus.md +++ b/docs/zh/msg_docs/PurePursuitStatus.md @@ -11,6 +11,4 @@ float32 crosstrack_error # [m] Shortest distance from the vehicle to the pat float32 distance_to_waypoint # [m] Distance from the vehicle to the current waypoint float32 bearing_to_waypoint # [rad] Bearing towards current waypoint -# TOPICS pure_pursuit_status - ``` diff --git a/docs/zh/msg_docs/RateCtrlStatus.md b/docs/zh/msg_docs/RateCtrlStatus.md index c6a4323ae9..90eaa1208f 100644 --- a/docs/zh/msg_docs/RateCtrlStatus.md +++ b/docs/zh/msg_docs/RateCtrlStatus.md @@ -9,6 +9,5 @@ uint64 timestamp # time since system start (microseconds) float32 rollspeed_integ float32 pitchspeed_integ float32 yawspeed_integ -float32 wheel_rate_integ # FW only and optional ``` diff --git a/docs/zh/msg_docs/RoverAttitudeSetpoint.md b/docs/zh/msg_docs/RoverAttitudeSetpoint.md index fc2bc4d639..778d4407a9 100644 --- a/docs/zh/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/zh/msg_docs/RoverAttitudeSetpoint.md @@ -7,6 +7,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_setpoint # [rad] Expressed in NED frame -# TOPICS rover_attitude_setpoint - ``` diff --git a/docs/zh/msg_docs/RoverAttitudeStatus.md b/docs/zh/msg_docs/RoverAttitudeStatus.md index 28d9ef6d96..24dc3cf12f 100644 --- a/docs/zh/msg_docs/RoverAttitudeStatus.md +++ b/docs/zh/msg_docs/RoverAttitudeStatus.md @@ -8,6 +8,4 @@ uint64 timestamp # time since system start (microseconds) float32 measured_yaw # [rad/s] Measured yaw rate float32 adjusted_yaw_setpoint # [rad/s] Yaw setpoint that is being tracked (Applied slew rates) -# TOPICS rover_attitude_status - ``` diff --git a/docs/zh/msg_docs/RoverPositionSetpoint.md b/docs/zh/msg_docs/RoverPositionSetpoint.md new file mode 100644 index 0000000000..8450bf8486 --- /dev/null +++ b/docs/zh/msg_docs/RoverPositionSetpoint.md @@ -0,0 +1,15 @@ +# RoverPositionSetpoint (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32[2] position_ned # 2-dimensional position setpoint in NED frame [m] +float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position) +float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed) +float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero) + +float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw) + +``` diff --git a/docs/zh/msg_docs/RoverRateSetpoint.md b/docs/zh/msg_docs/RoverRateSetpoint.md index 71755a38f3..12fe8cb88c 100644 --- a/docs/zh/msg_docs/RoverRateSetpoint.md +++ b/docs/zh/msg_docs/RoverRateSetpoint.md @@ -7,6 +7,4 @@ uint64 timestamp # time since system start (microseconds) float32 yaw_rate_setpoint # [rad/s] Expressed in NED frame -# TOPICS rover_rate_setpoint - ``` diff --git a/docs/zh/msg_docs/RoverRateStatus.md b/docs/zh/msg_docs/RoverRateStatus.md index 1f54694ee0..a3aa1d1164 100644 --- a/docs/zh/msg_docs/RoverRateStatus.md +++ b/docs/zh/msg_docs/RoverRateStatus.md @@ -9,6 +9,4 @@ float32 measured_yaw_rate # [rad/s] Measured yaw rate float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint that is being tracked (Applied slew rates) float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller -# TOPICS rover_rate_status - ``` diff --git a/docs/zh/msg_docs/RoverSteeringSetpoint.md b/docs/zh/msg_docs/RoverSteeringSetpoint.md index 1a6f3203dd..48353ea957 100644 --- a/docs/zh/msg_docs/RoverSteeringSetpoint.md +++ b/docs/zh/msg_docs/RoverSteeringSetpoint.md @@ -5,9 +5,8 @@ ```c uint64 timestamp # time since system start (microseconds) -float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Only for Ackermann-steered rovers) -float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Only for Differential/Mecanum rovers) +float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Ackermann only, Positiv: Steer right, Negativ: Steer left) -# TOPICS rover_steering_setpoint +float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Differential/Mecanum only, Positiv = Turn right, Negativ: Turn left) ``` diff --git a/docs/zh/msg_docs/RoverThrottleSetpoint.md b/docs/zh/msg_docs/RoverThrottleSetpoint.md index 9533126dd0..ccdf76902d 100644 --- a/docs/zh/msg_docs/RoverThrottleSetpoint.md +++ b/docs/zh/msg_docs/RoverThrottleSetpoint.md @@ -6,9 +6,7 @@ uint64 timestamp # time since system start (microseconds) -float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] -float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] - -# TOPICS rover_throttle_setpoint +float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] (Positiv = forwards, Negativ = backwards) +float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] (Mecanum only, Positiv = right, Negativ = left) ``` diff --git a/docs/zh/msg_docs/RoverVelocitySetpoint.md b/docs/zh/msg_docs/RoverVelocitySetpoint.md new file mode 100644 index 0000000000..2e2d322b47 --- /dev/null +++ b/docs/zh/msg_docs/RoverVelocitySetpoint.md @@ -0,0 +1,12 @@ +# RoverVelocitySetpoint (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocitySetpoint.msg) + +```c +uint64 timestamp # time since system start (microseconds) + +float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative) +float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction] +float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame + +``` diff --git a/docs/zh/msg_docs/RoverVelocityStatus.md b/docs/zh/msg_docs/RoverVelocityStatus.md index 02b2c3b527..c908ffac90 100644 --- a/docs/zh/msg_docs/RoverVelocityStatus.md +++ b/docs/zh/msg_docs/RoverVelocityStatus.md @@ -6,14 +6,10 @@ uint64 timestamp # time since system start (microseconds) float32 measured_speed_body_x # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards -float32 speed_body_x_setpoint # [m/s] Speed setpoint in body x direction. Positiv: forwards, Negativ: backwards float32 adjusted_speed_body_x_setpoint # [m/s] Post slew rate speed setpoint in body x direction. Positiv: forwards, Negativ: backwards -float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left -float32 speed_body_y_setpoint # [m/s] Speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) -float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Only for mecanum rovers) float32 pid_throttle_body_x_integral # Integral of the PID for the closed loop controller of the speed in body x direction -float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction - -# TOPICS rover_velocity_status +float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Mecanum only) +float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction (Mecanum only) ``` diff --git a/docs/zh/msg_docs/TrajectorySetpoint6dof.md b/docs/zh/msg_docs/TrajectorySetpoint6dof.md new file mode 100644 index 0000000000..f2629e19c4 --- /dev/null +++ b/docs/zh/msg_docs/TrajectorySetpoint6dof.md @@ -0,0 +1,23 @@ +# TrajectorySetpoint6dof (UORB message) + +Trajectory setpoint in NED frame +Input to position controller. + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TrajectorySetpoint6dof.msg) + +```c +# Trajectory setpoint in NED frame +# Input to position controller. + +uint64 timestamp # time since system start (microseconds) + +# NED local world frame +float32[3] position # in meters +float32[3] velocity # in meters/second +float32[3] acceleration # in meters/second^2 +float32[3] jerk # in meters/second^3 (for logging only) + +float32[4] quaternion # unit quaternion +float32[3] angular_velocity # angular velocity in radians/second + +``` diff --git a/docs/zh/msg_docs/VehicleAttitudeSetpoint.md b/docs/zh/msg_docs/VehicleAttitudeSetpoint.md index e8dc7ebaf9..9cd9ba092b 100644 --- a/docs/zh/msg_docs/VehicleAttitudeSetpoint.md +++ b/docs/zh/msg_docs/VehicleAttitudeSetpoint.md @@ -3,7 +3,7 @@ [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) ```c -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # time since system start (microseconds) @@ -16,10 +16,6 @@ float32[4] q_d # Desired quaternion for quaternion control # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] -bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) - -bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) - # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint ``` diff --git a/docs/zh/msg_docs/VehicleAttitudeSetpointV0.md b/docs/zh/msg_docs/VehicleAttitudeSetpointV0.md new file mode 100644 index 0000000000..6eb03e797c --- /dev/null +++ b/docs/zh/msg_docs/VehicleAttitudeSetpointV0.md @@ -0,0 +1,25 @@ +# VehicleAttitudeSetpointV0 (UORB message) + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg) + +```c +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # time since system start (microseconds) + +float32 yaw_sp_move_rate # rad/s (commanded by user) + +# For quaternion-based attitude control +float32[4] q_d # Desired quaternion for quaternion control + +# For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. +# For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. +float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] + +bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) + +bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) + +# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint + +``` diff --git a/docs/zh/msg_docs/VehicleCommand.md b/docs/zh/msg_docs/VehicleCommand.md index c2cc25f241..19557cf496 100644 --- a/docs/zh/msg_docs/VehicleCommand.md +++ b/docs/zh/msg_docs/VehicleCommand.md @@ -11,127 +11,127 @@ Follows the MAVLink COMMAND_INT / COMMAND_LONG definition uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start. -uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command -uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command -uint16 VEHICLE_CMD_CUSTOM_2 = 2 # test command -uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |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_PRECLAND = 23 # Attempt a precision landing -uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |Major Radius [m] |Minor Radius [m] |Velocity [m/s] |Orientation |Latitude/X |Longitude/Y |Altitude/Z | -uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| -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_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_CONDITION_GATE = 4501 # Wait until passing a threshold |2D coord mode: 0: Orthogonal to planned route | Altitude mode: 0: Ignore altitude| Empty| Empty| Lat| Lon| Alt| -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 cycles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| 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_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value |Altitude| Frame of new altitude | Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1| Actuator 2| Actuator 3| Actuator 4| Actuator 5| Actuator 6| Index| -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 autonomous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |Ground speed [m/s] |Bitmask |Loiter radius [m] for planes |Yaw [deg] |Latitude |Longitude |Altitude | +uint16 VEHICLE_CMD_CUSTOM_0 = 0 # Test command. +uint16 VEHICLE_CMD_CUSTOM_1 = 1 # Test command. +uint16 VEHICLE_CMD_CUSTOM_2 = 2 # Test command. +uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |[s] (decimal) Hold time. (ignored by fixed wing, time to stay at MISSION for rotary wing)|[m] Acceptance radius (if the sphere with this radius is hit, the MISSION counts as reached)|0 to pass through the WP, if > 0 radius [m] to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.|Desired yaw angle at MISSION (rotary wing)|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time. |Unused|Unused|[m] Radius around MISSION. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns. |Turns|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for time. |[s] Seconds (decimal)|Unused|Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand. |Unused (FW pitch from FW_TKO_PITCH_MIN)|Unused|Unused|[deg] [@range 0,360] Yaw angle in NED if yaw source available, ignored otherwise|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude AMSL| +uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing. +uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |[m] Radius|[m/s] Velocity|[@enum ORBIT_YAW_BEHAVIOUR] Yaw behaviour|Unused|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |[m] Major radius|[m] Minor radius|[m/s] Velocity|Orientation|Latitude/X|Longitude/Y|Altitude/Z| +uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| +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|Unused|[deg] [@range 0, 360] Yaw angle at goal, in compass degrees|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|Unused|Unused|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. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min AMSL - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time. |[s] Delay (decimal, -1 to enable time-of-day fields)|[h] hour (24h format, UTC, -1 to ignore)|minute (24h format, UTC, -1 to ignore)|second (24h format, UTC)|Unused|Unused|Unused| +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.|Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |[s] Delay (decimal seconds)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached.|Descent / Ascend rate (m/s)|Unused|Unused|Unused|Unused|Unused|Finish Altitude| +uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance [m]|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |[deg] [@range 0,360] Target angle. 0 is north|[deg/s] Speed during yaw change|[@range -1,1] Direction: negative: counter clockwise, positive: clockwise |[ 1,0] Relative offset or absolute angle|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_CONDITION_GATE = 4501 # Wait until passing a threshold. |2D coord mode: 0: Orthogonal to planned route|Altitude mode: 0: Ignore altitude|Unused|Unused|Lat|Lon|Alt| +uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE|Unused|Unused|Unused|Unused|Unused|Unused| +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|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |[@enum SPEED_TYPE] Speed type (0=Airspeed, 1=Ground Speed)|Speed (m/s, -1 indicates no change)|[%] Throttle ( Percent, -1 indicates no change)|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|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|Unused|Unused|Unused|Unused|Unused| +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)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cycles with a desired period. |Relay number|Cycle count|[s] Cycle time (decimal seconds)|Unused|Unused|Unused|Unused| +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|[us] PWM rate (1000 to 2000 typical)|Cycle count|[s] Cycle time|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately. |Flight termination activated if > 0.5|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value. |Altitude|Frame of new altitude|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1|Actuator 2|Actuator 3|Actuator 4|Actuator 5|Actuator 6|Index| +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. |Unused|Unused|Unused|Unused|Latitude|Longitude|Unused| +uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonomous landing. |[m] Altitude|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_REPOSITION = 192 # Reposition to specific WGS84 GPS position. |[m/s] Ground speed|Bitmask|[m] Loiter radius for planes|[deg] Yaw|Latitude|Longitude|Altitude| uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193 -uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude| -uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint| -uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| +uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Latitude|Longitude|Altitude| +uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Pitch offset from next waypoint|Roll offset from next waypoint|Yaw offset from next waypoint| +uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)|Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw|Transmission mode: 0: video stream, >0: single images every n seconds (decimal seconds)|Recording: 0: disabled, 1: enabled compressed, 2: enabled raw|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z| uint16 VEHICLE_CMD_DO_DIGICAM_CONTROL=203 -uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # motor test command |Instance (1, ...)| throttle type| throttle| timeout [s]| Motor count | Test order| Empty| -uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper -uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # 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_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See mavlink spec MAV_CMD_PREFLIGHT_CALIBRATION -uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration -uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| -uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started -uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| -uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty| -uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode |MAV_STANDARD_MODE| -uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal +uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount. |[@enum MAV_MOUNT_MODE] Mount operation mode|Stabilize roll? (1 = yes, 0 = no)|Stabilize pitch? (1 = yes, 0 = no)|stabilize yaw? (1 = yes, 0 = no)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount. |[deg] Pitch or lat, depending on mount mode.|[deg] Roll or lon depending on mount mode|[deg]/[m] Yaw or alt depending on mount mode|Unused|Unused|Unused|[@enum MAV_MOUNT_MODE]| +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence. |enable? (0=disable, 1=enable)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute. |action [@enum PARACHUTE_ACTION] (0=disable, 1=enable, 2=release, for some systems see [@enum PARACHUTE_ACTION], not in general message set.)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # Motor test command. |Instance (@range 1, )|throttle type|throttle|timeout [s]|Motor count|Test order|Unused| +uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight. |inverted (0=normal, 1=inverted)|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper. +uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight. |[m] Camera trigger distance|Shutter integration time (ms)|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)|q2 - quaternion param #2, x (0 in null-rotation)|q3 - quaternion param #3, y (0 in null-rotation)|q4 - quaternion param #4, z (0 in null-rotation)|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min(AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (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|Unused|Unused|Unused| +uint16 VEHICLE_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration. |Unused|Unused|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See MAVLink spec MAV_CMD_PREFLIGHT_CALIBRATION. +uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# Param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration. +uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow|X axis offset (or generic dimension 1), in the sensor's raw units|Y axis offset (or generic dimension 2), in the sensor's raw units|Z axis offset (or generic dimension 3), in the sensor's raw units|Generic dimension 4, in the sensor's raw units|Generic dimension 5, in the sensor's raw units|Generic dimension 6, in the sensor's raw units| +uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started. +uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.|0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.|Unused|Unused|Unused|Unused|Unused| +uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight. |[m] Camera trigger distance|[ms] Shutter integration time|Camera minimum trigger interval|Number of positions|Roll|Pitch|Unused| +uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode. |MAV_STANDARD_MODE| +uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal. -uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| -uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command|value [-1,1]|timeout [s]|Empty|Empty|output function| -uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|configuration|Empty|Empty|Empty|output function| -uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm -uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. -uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes -uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| -uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message -uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| -uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.) -uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom +uint16 VEHICLE_CMD_MISSION_START = 300 # Start running a mission. |first_item: the first mission item to run|last_item: the last mission item to run (after this item is run, the mission ends)| +uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command. |[@range -1,1] value|[s] timeout|Unused|Unused|output function| +uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command. |configuration|Unused|Unused|Unused|output function| +uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component. |1 to arm, 0 to disarm. +uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks. +uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes. +uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing. |0:Spektrum|0:Spektrum DSM2, 1:Spektrum DSMX| +uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message. +uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities|Reserved (all remaining params)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)|Reserved (default:0)| +uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). +uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw -uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control -uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. -uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system -uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. -uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. -uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data -uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data -uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link -uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition -uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization -uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan -uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment -uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. -uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. +uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. +uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. +uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture. +uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture. +uint16 VEHICLE_CMD_LOGGING_START = 2510 # Start streaming ULog data. +uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # Stop streaming ULog data. +uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # Control starting/stopping transmitting data over the high latency link. +uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition. +uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization. +uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan. +uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment. +uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. +uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch. -uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # external reset of estimator global position when deadreckoning +uint16 VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE = 43003 # External reset of estimator global position when dead reckoning. uint16 VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE = 43004 -# PX4 vehicle commands (beyond 16 bit mavlink commands) -uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX) -uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude| -uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty| +# PX4 vehicle commands (beyond 16 bit MAVLink commands). +uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # Start of PX4 internal only vehicle commands (> UINT16_MAX). +uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Unused|Unused|Unused|Unused|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude (AMSL from GNSS, positive above ground)| +uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Unused|Unused|Unused|Unused|Unused|Unused| -uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization | -uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | -uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | -uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt | -uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # +uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization. +uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization. +uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt. +uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 # -uint8 VEHICLE_ROI_NONE = 0 # No region of interest | -uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | -uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | -uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | -uint8 VEHICLE_ROI_TARGET = 4 # Point toward target +uint8 VEHICLE_ROI_NONE = 0 # No region of interest. +uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION. +uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION. +uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location. +uint8 VEHICLE_ROI_TARGET = 4 # Point toward target. uint8 VEHICLE_ROI_ENUM_END = 5 uint8 PARACHUTE_ACTION_DISABLE = 0 @@ -163,13 +163,13 @@ uint8 FAILURE_TYPE_SLOW = 5 uint8 FAILURE_TYPE_DELAYED = 6 uint8 FAILURE_TYPE_INTERMITTENT = 7 -# used as param1 in DO_CHANGE_SPEED command +# Used as param1 in DO_CHANGE_SPEED command. uint8 SPEED_TYPE_AIRSPEED = 0 uint8 SPEED_TYPE_GROUNDSPEED = 1 uint8 SPEED_TYPE_CLIMB_SPEED = 2 uint8 SPEED_TYPE_DESCEND_SPEED = 3 -# used as param3 in CMD_DO_ORBIT +# Used as param3 in CMD_DO_ORBIT. uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0 uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 @@ -177,29 +177,29 @@ uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 -# used as param1 in ARM_DISARM command +# Used as param1 in ARM_DISARM command. int8 ARMING_ACTION_DISARM = 0 int8 ARMING_ACTION_ARM = 1 -# param2 in VEHICLE_CMD_DO_GRIPPER +# param2 in VEHICLE_CMD_DO_GRIPPER. uint8 GRIPPER_ACTION_RELEASE = 0 uint8 GRIPPER_ACTION_GRAB = 1 uint8 ORB_QUEUE_LENGTH = 8 -float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. -float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. -float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. -uint32 command # Command ID -uint8 target_system # System which should execute the command -uint8 target_component # Component which should execute the command, 0 for all components -uint8 source_system # System sending the command -uint16 source_component # Component / mode executor sending the command -uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. +float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. +float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. +uint32 command # Command ID. +uint8 target_system # System which should execute the command. +uint8 target_component # Component which should execute the command, 0 for all components. +uint8 source_system # System sending the command. +uint16 source_component # Component / mode executor sending the command. +uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command). bool from_external uint16 COMPONENT_MODE_EXECUTOR_START = 1000 diff --git a/docs/zh/msg_docs/index.md b/docs/zh/msg_docs/index.md index 4e369d6afb..3ba767d12e 100644 --- a/docs/zh/msg_docs/index.md +++ b/docs/zh/msg_docs/index.md @@ -15,10 +15,18 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message +- [AirspeedValidated](AirspeedValidated.md) - [ArmingCheckReply](ArmingCheckReply.md) - [ArmingCheckRequest](ArmingCheckRequest.md) - [BatteryStatus](BatteryStatus.md) - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors +- [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message + Used by the fw_lateral_longitudinal_control module + At least one of course, airspeed_direction, or lateral_acceleration must be finite. +- [FixedWingLongitudinalSetpoint](FixedWingLongitudinalSetpoint.md) — Fixed Wing Longitudinal Setpoint message + Used by the fw_lateral_longitudinal_control module + If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. + If both altitude and height_rate are NAN, the controller maintains the current altitude. - [GotoSetpoint](GotoSetpoint.md) — Position and (optional) heading setpoints with corresponding speed constraints Setpoints are intended as inputs to position and heading smoothers, respectively Setpoints do not need to be kinematically consistent @@ -26,6 +34,11 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m Unset optional setpoints are not controlled Unset optional constraints default to vehicle specifications - [HomePosition](HomePosition.md) — GPS home position in WGS84 coordinates. +- [LateralControlConfiguration](LateralControlConfiguration.md) — Fixed Wing Lateral Control Configuration message + Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. +- [LongitudinalControlConfiguration](LongitudinalControlConfiguration.md) — Fixed Wing Longitudinal Control Configuration message + Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages + and configure the resultant setpoints. - [ManualControlSetpoint](ManualControlSetpoint.md) - [ModeCompleted](ModeCompleted.md) — Mode completion result, published by an active mode. The possible values of nav_state are defined in the VehicleStatus msg. @@ -79,8 +92,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [Airspeed](Airspeed.md) -- [AirspeedValidated](AirspeedValidated.md) - - [AirspeedWind](AirspeedWind.md) - [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) @@ -95,7 +106,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [CanInterfaceStatus](CanInterfaceStatus.md) -- [CellularStatus](CellularStatus.md) +- [CellularStatus](CellularStatus.md) — Cellular status - [CollisionConstraints](CollisionConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -164,6 +175,14 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [FigureEightStatus](FigureEightStatus.md) +- [FixedWingLateralGuidanceStatus](FixedWingLateralGuidanceStatus.md) — Fixed Wing Lateral Guidance Status message + Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs + +- [FixedWingLateralStatus](FixedWingLateralStatus.md) — Fixed Wing Lateral Status message + Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint + +- [FixedWingRunwayControl](FixedWingRunwayControl.md) — Auxiliary control fields for fixed-wing runway takeoff/landing + - [FlightPhaseEstimation](FlightPhaseEstimation.md) - [FollowTarget](FollowTarget.md) @@ -270,8 +289,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md) -- [NpfgStatus](NpfgStatus.md) - - [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor. - [OffboardControlMode](OffboardControlMode.md) — Off-board control mode @@ -343,6 +360,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverAttitudeStatus](RoverAttitudeStatus.md) +- [RoverPositionSetpoint](RoverPositionSetpoint.md) + - [RoverRateSetpoint](RoverRateSetpoint.md) - [RoverRateStatus](RoverRateStatus.md) @@ -351,6 +370,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) +- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) + - [RoverVelocityStatus](RoverVelocityStatus.md) - [Rpm](Rpm.md) @@ -419,6 +440,9 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [TimesyncStatus](TimesyncStatus.md) +- [TrajectorySetpoint6dof](TrajectorySetpoint6dof.md) — Trajectory setpoint in NED frame + Input to position controller. + - [TransponderReport](TransponderReport.md) - [TuneControl](TuneControl.md) — This message is used to control the tunes, when the tune_id is set to CUSTOM @@ -471,4 +495,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [YawEstimatorStatus](YawEstimatorStatus.md) +- [AirspeedValidatedV0](AirspeedValidatedV0.md) + +- [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md) + - [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander \ No newline at end of file diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index cc3efabd54..cd1cf57694 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -345,6 +345,7 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: - [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -359,7 +360,7 @@ You can add your own setpoint types by adding a class that inherits from `px4_ro This setpoint type is currently only supported for multicopters. ::: -Smoothly control position and (optionally) heading setpoints with the [px4_ros2::GotoSetpointType](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. The most trivial use is simply inputting a 3D position into the update method: @@ -404,6 +405,137 @@ _goto_setpoint->update( max_heading_rate_rad_s); ``` +#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) + + + +:::info +This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. +::: + +Use the [`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html) to directly control the lateral and longitudinal dynamics of a fixed-wing vehicle — that is, side-to-side motion (turning/banking) and forward/vertical motion (speeding up and climbing/descending), respectively. +This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../modules/modules_controller.md#fw-lat-lon-control), which decouples lateral and longitudinal inputs while ensuring that vehicle limits are respected. + +To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: + +1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. + If both are set to `NAN`, the vehicle will maintain its current altitude. +2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. + +For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). + +##### 基本用法 + +This type has a number of update methods, each allowing you to specify an increasing number of setpoints. + +The simplest method is `updateWithAltitude()`, which allows you to specify a `course` and `altitude` target setpoint: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, course); +``` + +PX4 uses the setpoints to compute the _roll angle_, _pitch angle_ and _throttle_ setpoints that are sent to lower level controllers. +Note that the commanded flight is expected to be relatively gentle/unaggressive when using this method. +This is done as follows: + +- Lateral control output: + + course setpoint (set by user) → airspeed direction (heading) setpoint → lateral acceleration setpoint → roll angle setpoint. + +- Longitudinal control output: + + altitude setpoint (set by user) → height rate setpoint → pitch angle setpoint and throttle settings. + +The `updateWithHeightRate()` method allows you to set a target `course` and `height_rate` (this is useful if the speed of ascent or descent matters, or needs to be dynamically controlled): + +```cpp +const float height_rate = 2.F; +const float course = 0.F; // due North +_fw_lateral_longitudinal_setpoint->updateWithHeightRate(height_rate, course); +``` + +The `updateWithAltitude()` and `updateWithHeightRate()` methods allow you to additionally control the equivalent airspeed or lateral acceleration by specifying them as the third and fourth arguments, respectively: + +```cpp +const float altitude_msl = 500.F; +const float course = 0.F; // due North +const float equivalent_aspd = 15.F; // m/s +const float lateral_acceleration = 2.F; // FRD, used as feedforward + +_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, + course, + equivalent_aspd, + lateral_acceleration); +``` + +The equivalent airspeed and lateral acceleration arguments are defined as `std::optional`, so you can omit any of them by passing `std::nullopt`. + +:::tip +If both lateral acceleration and course setpoints are provided, the lateral acceleration setpoint will be used as feedforward. +::: + +##### Full Control Using the Setpoint Struct + +For full flexibility, you can create and pass a [`FwLateralLongitudinalSetpoint`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwLateralLongitudinalSetpoint.html) struct. +Each field is templated with `std::optional`. + +:::tip +If both course and airspeed direction are set: airspeed direction takes precedence, course is not controlled. +Lateral acceleration is treated as feedforward if either course or airspeed direction are also finite. +If both altitude and height rate are set: height rate takes precedence, altitude is not controlled. +::: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withCourse(0.F); +// setpoint_s.withAirspeedDirection(0.2F); // uncontrolled +setpoint_s.withLateralAcceleration(2.F); // feedforward +//setpoint_s.withAltitude(500.F); // uncontrolled +setpoint_s.withHeightRate(2.F); +setpoint_s.withEquivalentAirspeed(15.F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s); +``` + +The diagram below illustrates the interaction between the `FwLateralLongitudinalSetpointType` and PX4 when all inputs are set. + +![FW ROS Interaction](../../assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg) + +##### Advanced Configuration (Optional) + +You can also pass a [`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) struct along with the setpoint to override default controller settings and constraints such as pitch limits, throttle limits, and target sink/climb rates. +This is intended for advanced users: + +```cpp +px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; + +setpoint_s.withAirspeedDirection(0.F); +setpoint_s.withLateralAcceleration(2.F); // feedforward +setpoint_s.withAltitude(500.F); +setpoint_s.withEquivalentAirspeed(15.F); + +px4_ros2::FwControlConfiguration config_s; + +config_s.withTargetClimbRate(3.F); +config_s.withMaxAcceleration(5.F); +config_s.withThrottleLimits(0.4F, 0.6F); + +_fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); +``` + +All configuration fields are defined as `std::optional`. +Unset values will default to the PX4 configuration. +See [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) and [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md) for more information on configuration options. + +:::info +For safety, PX4 automatically limits configuration values to stay within the vehicle’s constraints. +For example, throttle overrides are clamped to remain between [`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) +and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). +::: + #### Direct Actuator Control Setpoint (DirectActuatorsSetpointType) Actuators can be directly controlled using the [px4_ros2::DirectActuatorsSetpointType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) setpoint type. @@ -415,11 +547,55 @@ For example to control a quadrotor, you need to set the first 4 motors according If you want to control an actuator that does not control the vehicle's motion, but for example a payload servo, see [below](#controlling-an-independent-actuator-servo). ::: +### Controlling a VTOL + + + +To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: + +- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). + +As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. + +If you would like to command a VTOL transition in your external mode, you need to use the [VTOL API](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1VTOL.html). The VTOL API provides the functionality to command a transition and query the current state of the vehicle. + +Use this API with caution! +Commanding transitions externally makes the user partially responsible for ensuring smooth and safe behavior, unlike onboard transitions (e.g. via RC switch) where PX4 handles the full process: + +1. Ensure that both the `TrajectorySetpointType` and the `FwLateralLongitudinalSetpointType` are available to your mode. +2. Create an instance of `px4_ros2::VTOL` in the constructor of your mode. +3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. +4. During transition, send the following combination of setpoints: + + ```cpp + // Assuming the instance of the px4_ros2::VTOL object is called vtol + + // Send TrajectorySetpointType as follows: + Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); + Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; + + _trajectory_setpoint->update(velocity_sp, acceleration_sp); + + // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired + + float course_sp = 0.F; // North + + _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) + ``` + + This will ensure that the transition is handled properly within PX4. + You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + +To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. + +See [this external flight mode implementation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol) for a practical example on how to use this API. + ### Controlling an Independent Actuator/Servo If you want to control an independent actuator (a servo), follow these steps: -1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink) +1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). 2. Create an instance of [px4_ros2::PeripheralActuatorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html) in the constructor of your mode. 3. Call the `set()` method to control the actuator(s). This can be done independently of any active setpoints. @@ -431,6 +607,7 @@ You can access PX4 telemetry topics directly via the following classes: - [OdometryGlobalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryGlobalPosition.html): Global position - [OdometryLocalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryLocalPosition.html): Local position, velocity, acceleration, and heading - [OdometryAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAttitude.html): Vehicle attitude +- [OdometryAirspeed](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAirspeed.html): Airspeed For example, you can query the vehicle's current position estimate as follows: diff --git a/docs/zh/sim_gazebo_gz/index.md b/docs/zh/sim_gazebo_gz/index.md index 4c3c1fa6e7..34c383c3c9 100644 --- a/docs/zh/sim_gazebo_gz/index.md +++ b/docs/zh/sim_gazebo_gz/index.md @@ -396,6 +396,11 @@ As long as the world file and the model file are in the Gazebo search path (`GZ_ However, `make px4_sitl gz__` won't work with them. ::: +## Extending Gazebo with Plugins + +World, vehicle (model), and sensor behaviour can be customised using plugins. +For more information see [Gazebo Plugins](../sim_gazebo_gz/plugins.md). + ## 基于gazebo的多飞行器仿真 Multi-Vehicle simulation is supported on Linux hosts. diff --git a/docs/zh/sim_gazebo_gz/plugins.md b/docs/zh/sim_gazebo_gz/plugins.md new file mode 100644 index 0000000000..9723f44177 --- /dev/null +++ b/docs/zh/sim_gazebo_gz/plugins.md @@ -0,0 +1,92 @@ +# Gazebo Plugins + +Gazebo plugins extend the simulator with custom functionality not provided by default. They can be attached to different entity types and allow you to add new sensors, modify world physics, or interact with the simulation environment. + +## Plugin Types + +Plugins can be attached to these entity types: + +- **World** - Global simulation behavior +- **Model** - Specific model functionality +- **Sensor** - Custom sensor implementations +- **Actor** - Dynamic entity behavior + +## Supported Plugins + +PX4 currently supports these plugins: + +- [OpticalFlowSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/optical_flow): Provides optical flow sensor simulation using OpenCV-based flow calculation. +- [GstCameraSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/gstreamer): Streams camera feeds via UDP (RTP/H.264) or RTMP with optional NVIDIA CUDA hardware acceleration. +- [MovingPlatformController](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/moving_platform_controller): Controls moving platforms (ships, trucks, etc.) for takeoff and landing scenarios. + Includes configurable velocity, heading, and random fluctuations. + +## Plugin Registration + +Plugins must be registered in the [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) file to be available in your world: + +```xml + + + + + + + + + + +``` + +## Creating Custom Plugins + +When developing new plugins: + +1. **Follow the plugin architecture** - Implement desired interfaces. + + You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. + The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). + +2. **Register your plugin** - Add it to [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) for discovery. + +3. **Use the custom namespace** - Follow the pattern `custom::YourPluginName`. + +### Example Plugin Structure + +```cpp +class YourCustomSystem : + public gz::sim::System, + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemPostUpdate +{ +public: + void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; + void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; +}; + +// Plugin registration +GZ_ADD_PLUGIN(YourCustomSystem, gz::sim::System, + YourCustomSystem::ISystemPreUpdate, + YourCustomSystem::ISystemPostUpdate) +GZ_ADD_PLUGIN_ALIAS(YourCustomSystem, "custom::YourCustomSystem") +``` + +## Enabling a Plugin + +For world plugins all you need to do is [register the plugin](#plugin-registration) (add it to the `server.config`). +It will then be available to all worlds and vehicles. + +The process for adding vehicle model/sensor plugins is not documented. +This can tracked through [PX4-Autopilot#2493](https://github.com/PX4/PX4-Autopilot/issues/24939). + +## Resources + +- **PX4 Plugins**: [Repository source code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins) +- **Official Gazebo Documentation**: [System Plugins Guide](https://gazebosim.org/api/sim/9/createsystemplugins.html) +- **Server Configuration**: [Configuration Reference](https://gazebosim.org/api/sim/9/server_config.html) +- **PX4 Gazebo-classic Plugins**: [PX4 Gazebo Classic Plugins](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/main/src) + +:::info +Plugins for modern Gazebo are still evolving. The plugin system differs from Gazebo Classic. +::: diff --git a/docs/zh/telemetry/crsf_telemetry.md b/docs/zh/telemetry/crsf_telemetry.md index 8abc6fdf76..37cc7b10c2 100644 --- a/docs/zh/telemetry/crsf_telemetry.md +++ b/docs/zh/telemetry/crsf_telemetry.md @@ -71,7 +71,7 @@ For ExpressLRS receivers wire to the flight controller UART as shown below (wiri ### Firmware Configuration/Build CRSF telemetry support is not included in any PX4 firmware by default. -To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver.md#crsf-rc) and removes [rc_input](../modules/modules_driver.md#rc-input). +To use this feature you must build and upload custom firmware that includes [crsf-rc](../modules/modules_driver_radio_control.md#crsf-rc) and removes [rc_input](../modules/modules_driver_radio_control.md#rc-input). 步骤如下: diff --git a/docs/zh/tutorials/linux_sbus.md b/docs/zh/tutorials/linux_sbus.md index 0aecc4c85d..18b037fde0 100644 --- a/docs/zh/tutorials/linux_sbus.md +++ b/docs/zh/tutorials/linux_sbus.md @@ -10,9 +10,7 @@ For an S.Bus receiver (or encoder - e.g. from Futaba, RadioLink, etc.) you will Then [Start the PX4 RC Driver](#start_driver) on the device, as shown below. - - -## 启动驱动程序 +## Starting the Driver {#start_driver} To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): @@ -20,11 +18,9 @@ To start the RC driver on a particular UART (e.g. in this case `/dev/ttyS2`): linux_sbus start|stop|status -d <device> -c <channel> ``` -For other driver usage information see: [rc_input](../modules/modules_driver.md#rc-input). +For other driver usage information see: [rc_input](../modules/modules_driver_radio_control.md#rc-input). - - -## 信号反相器电路 (仅限S.Bus) +## Signal Inverter Circuit (S.Bus only) {#signal_inverter_circuit} S.Bus is an _inverted_ UART communication signal. From a2c23acc65462c45e3e98612b3ecc57f900af0e2 Mon Sep 17 00:00:00 2001 From: Beniamino Pozzan Date: Mon, 2 Jun 2025 03:33:09 +0100 Subject: [PATCH 080/130] fix (msp_ods): clear buffers before writing and adjust sizes (#24951) Signed-off-by: Beniamino Pozzan --- src/drivers/osd/msp_osd/msp_defines.h | 2 +- src/drivers/osd/msp_osd/uorb_to_msp.cpp | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/drivers/osd/msp_osd/msp_defines.h b/src/drivers/osd/msp_osd/msp_defines.h index 317c0b51f2..55eda1074c 100644 --- a/src/drivers/osd/msp_osd/msp_defines.h +++ b/src/drivers/osd/msp_osd/msp_defines.h @@ -462,7 +462,7 @@ struct msp_rendor_satellites_used_t { uint8_t iconIndex = 0x1E; //satellites icon uint8_t iconIndex2 = 0x1F; //satellites icon - char str[2]; // 99 + char str[3]; // 99 } __attribute__((packed)); diff --git a/src/drivers/osd/msp_osd/uorb_to_msp.cpp b/src/drivers/osd/msp_osd/uorb_to_msp.cpp index e64842fb88..2ffd57e5f2 100644 --- a/src/drivers/osd/msp_osd/uorb_to_msp.cpp +++ b/src/drivers/osd/msp_osd/uorb_to_msp.cpp @@ -378,6 +378,7 @@ msp_rendor_satellites_used_t construct_rendor_GPS_NUM(const sensor_gps_s &vehicl num.screenYPosition = 0x08; num.screenXPosition = 0x29; + memset(&num.str[0], 0, sizeof(num.str)); snprintf(&num.str[0], sizeof(num.str), "%d", vehicle_gps_position.satellites_used); return num; @@ -485,6 +486,7 @@ msp_rendor_pitch_t construct_rendor_PITCH(const vehicle_attitude_s &vehicle_att double pitch_deg = (double)math::degrees(euler_attitude.theta()); // attitude.roll = math::degrees(euler_attitude.phi()) * 10; + memset(&pit.str[0], 0, sizeof(pit.str)); snprintf(&pit.str[0], sizeof(pit.str), "%.1f", pitch_deg); return pit; @@ -503,6 +505,7 @@ msp_rendor_roll_t construct_rendor_ROLL(const vehicle_attitude_s &vehicle_attit // double pitch = (double)math::degrees(euler_attitude.theta()); double roll_deg = (double)math::degrees(euler_attitude.phi()); + memset(&roll.str[0], 0, sizeof(roll.str)); snprintf(&roll.str[0], sizeof(roll.str), "%.1f", roll_deg); return roll; From 8d3c94c94780f20b0deff691162fa648ba6484d6 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Mon, 2 Jun 2025 08:38:11 +0200 Subject: [PATCH 081/130] Baro offset calibration based on GNSS height (#24859) * apply offset to baro sensors based on gnss measurements when gnss is selected as hgt-ref * always calibrate baro with gnss if new param SENS_BAR_AUTOCAL is set accordingly * always do baro-gnss calibration when AUTOCALIB is set, but ensure epv is small enough and gnss data is consistent with baro * avoid update and reset in the same step * minor change of constexpr usage --- .../vehicle_air_data/VehicleAirData.cpp | 94 ++++++++++++++++++- .../vehicle_air_data/VehicleAirData.hpp | 12 ++- src/modules/sensors/vehicle_air_data/params.c | 12 +++ 3 files changed, 116 insertions(+), 2 deletions(-) diff --git a/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp b/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp index 49bbbcc90a..916f4802d5 100644 --- a/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp +++ b/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp @@ -256,6 +256,9 @@ void VehicleAirData::Run() if (!_relative_calibration_done) { _relative_calibration_done = UpdateRelativeCalibrations(time_now_us); + + } else if (!_baro_gnss_calibration_done && _param_sens_baro_autocal.get()) { + _baro_gnss_calibration_done = BaroGNSSAltitudeOffset(); } // Publish @@ -336,7 +339,7 @@ bool VehicleAirData::UpdateRelativeCalibrations(const hrt_abstime time_now_us) _calibration_t_first = time_now_us; } - if (time_now_us - _calibration_t_first > 1_s) { + if (time_now_us - _calibration_t_first > 1_s && _data_sum_count[_selected_sensor_sub_index] > 0) { const float pressure_primary = _data_sum[_selected_sensor_sub_index] / _data_sum_count[_selected_sensor_sub_index]; for (int instance = 0; instance < MAX_SENSOR_COUNT; ++instance) { @@ -469,4 +472,93 @@ void VehicleAirData::PrintStatus() } } +bool VehicleAirData::BaroGNSSAltitudeOffset() +{ + static constexpr float kEpvReq = 8.f; + static constexpr float kDeltaOffsetTolerance = 4.f; + static constexpr uint64_t kLpfWindow = 2_s; + static constexpr float kLpfTimeConstant = static_cast(kLpfWindow) * 1.e-6f; + + sensor_gps_s gps_pos; + + if (!_vehicle_gps_position_sub.update(&gps_pos)) { + return false; + } + + const float pressure_sealevel = _param_sens_baro_qnh.get() * 100.0f; + const float baro_pressure = _data_sum[_selected_sensor_sub_index] / _data_sum_count[_selected_sensor_sub_index]; + const float target_altitude = static_cast(gps_pos.altitude_msl_m); + + const float delta_alt = getAltitudeFromPressure(baro_pressure, pressure_sealevel) - target_altitude; + bool gnss_baro_offset_stable = false; + + if (gps_pos.epv > kEpvReq || _t_first_gnss_sample == 0) { + _calibration_t_first = 0; + _t_first_gnss_sample = gps_pos.timestamp; + return false; + } + + if (_calibration_t_first == 0) { + _calibration_t_first = gps_pos.timestamp; + const float dt = (_calibration_t_first - _t_first_gnss_sample) * 1.e-6f; + _delta_baro_gnss_lpf.setParameters(dt, kLpfTimeConstant); + _delta_baro_gnss_lpf.reset(delta_alt); + + } else { + _delta_baro_gnss_lpf.update(delta_alt); + } + + if (gps_pos.timestamp - _calibration_t_first > kLpfWindow && !PX4_ISFINITE(_baro_gnss_offset_t1)) { + _baro_gnss_offset_t1 = _delta_baro_gnss_lpf.getState(); + + } else if (gps_pos.timestamp - _calibration_t_first > 2 * kLpfWindow && PX4_ISFINITE(_baro_gnss_offset_t1)) { + if (fabsf(_delta_baro_gnss_lpf.getState() - _baro_gnss_offset_t1) > kDeltaOffsetTolerance) { + _baro_gnss_offset_t1 = NAN; + _calibration_t_first = 0; + _t_first_gnss_sample = 0; + + } else { + gnss_baro_offset_stable = true; + } + } + + if (!gnss_baro_offset_stable) { + return false; + } + + // Binary search + float low = -10000.0f; + float high = 10000.0f; + float offset = NAN; + static constexpr float kTolerance = 0.1f; + static constexpr int kIterations = 100; + + for (int i = 0; i < kIterations; ++i) { + float mid = low + (high - low) / 2.0f; + float calibrated_altitude = getAltitudeFromPressure(baro_pressure - mid, pressure_sealevel); + + if (calibrated_altitude > target_altitude + kTolerance) { + high = mid; + + } else if (calibrated_altitude < target_altitude - kTolerance) { + low = mid; + + } else { + offset = mid; + break; + } + } + + // add new offset to existing relative offsets + for (int instance = 0; instance < MAX_SENSOR_COUNT; ++instance) { + if (_calibration[instance].device_id() != 0 && _data_sum_count[instance] > 0) { + _calibration[instance].set_offset(_calibration[instance].offset() + offset); + _calibration[instance].ParametersSave(instance); + param_notify_changes(); + } + } + + return true; +} + }; // namespace sensors diff --git a/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp b/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp index 431e0867bb..d7620d48d0 100644 --- a/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp +++ b/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp @@ -36,6 +36,7 @@ #include "data_validator/DataValidatorGroup.hpp" #include +#include #include #include #include @@ -55,6 +56,7 @@ #include #include #include +#include using namespace time_literals; @@ -86,6 +88,7 @@ private: bool ParametersUpdate(bool force = false); void UpdateStatus(); bool UpdateRelativeCalibrations(hrt_abstime time_now_us); + bool BaroGNSSAltitudeOffset(); static constexpr int MAX_SENSOR_COUNT = 4; @@ -106,6 +109,8 @@ private: {this, ORB_ID(sensor_baro), 3}, }; + uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; + calibration::Barometer _calibration[MAX_SENSOR_COUNT]; perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; @@ -134,11 +139,16 @@ private: bool _last_status_baro_fault{false}; bool _relative_calibration_done{false}; + bool _baro_gnss_calibration_done{false}; uint64_t _calibration_t_first{0}; + AlphaFilter _delta_baro_gnss_lpf{}; + float _baro_gnss_offset_t1{NAN}; + uint64_t _t_first_gnss_sample{0}; DEFINE_PARAMETERS( (ParamFloat) _param_sens_baro_qnh, - (ParamFloat) _param_sens_baro_rate + (ParamFloat) _param_sens_baro_rate, + (ParamBool) _param_sens_baro_autocal ) }; }; // namespace sensors diff --git a/src/modules/sensors/vehicle_air_data/params.c b/src/modules/sensors/vehicle_air_data/params.c index fee8ac6263..0f32fee2f1 100644 --- a/src/modules/sensors/vehicle_air_data/params.c +++ b/src/modules/sensors/vehicle_air_data/params.c @@ -53,3 +53,15 @@ PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f); * @unit Hz */ PARAM_DEFINE_FLOAT(SENS_BARO_RATE, 20.0f); + +/** + * Barometer auto calibration + * + * Automatically calibrate barometer based on the GNSS height + * + * @boolean + * + * @category system + * @group Sensors + */ +PARAM_DEFINE_INT32(SENS_BAR_AUTOCAL, 0); From 2110da73adbd94f347feb4bd93d7dc31a8507056 Mon Sep 17 00:00:00 2001 From: Mahima Yoga Date: Mon, 2 Jun 2025 10:50:03 +0200 Subject: [PATCH 082/130] Commander: don't reset Home position if landed during a (uncompleted) mission. (#24902) --- src/modules/commander/Commander.cpp | 9 ++++++--- src/modules/commander/Commander.hpp | 1 + src/modules/commander/commander_params.c | 3 +++ 3 files changed, 10 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index cebc08ae94..ad5eccafb4 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -613,7 +613,7 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_ events::send(events::ID("commander_armed_by"), events::Log::Info, "Armed by {1}", calling_reason); - if (_param_com_home_en.get()) { + if (_param_com_home_en.get() && !_mission_in_progress) { _home_position.setHomePosition(); } @@ -1809,7 +1809,10 @@ void Commander::run() vtolStatusUpdate(); - _home_position.update(_param_com_home_en.get(), !isArmed() && _vehicle_land_detected.landed); + _mission_in_progress = (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) + && !_mission_result_sub.get().finished; + + _home_position.update(_param_com_home_en.get(), !isArmed() && _vehicle_land_detected.landed && !_mission_in_progress); handleAutoDisarm(); @@ -2110,7 +2113,7 @@ void Commander::landDetectorUpdate() } // automatically set or update home position - if (_param_com_home_en.get()) { + if (_param_com_home_en.get() && !_mission_in_progress) { // set the home position when taking off if (!_vehicle_land_detected.landed) { if (was_landed) { diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index af16a7f81d..1d7841cdc8 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -279,6 +279,7 @@ private: bool _arm_tune_played{false}; bool _have_taken_off_since_arming{false}; bool _status_changed{true}; + bool _mission_in_progress{false}; vehicle_land_detected_s _vehicle_land_detected{}; diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index c1b77b6721..3cd9b95f72 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -142,6 +142,9 @@ PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5f); * * Set home position automatically if possible. * + * During missions, the home position is locked and will not reset during intermediate landings. + * It will only update once the mission is complete or landed outside of a mission. + * * @group Commander * @reboot_required true * @boolean From 17cadf773903b9d0deed38434df11db6df76d2fd Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Tue, 27 May 2025 17:32:22 +0200 Subject: [PATCH 083/130] dds_topics: set more sensible ROS2 publication rate limits --- src/modules/uxrce_dds_client/dds_topics.yaml | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index 86f638a454..23cb5082dd 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -10,9 +10,11 @@ publications: - topic: /fmu/out/arming_check_request type: px4_msgs::msg::ArmingCheckRequest + rate_limit: 5. - topic: /fmu/out/mode_completed type: px4_msgs::msg::ModeCompleted + rate_limit: 50. - topic: /fmu/out/battery_status type: px4_msgs::msg::BatteryStatus @@ -20,66 +22,80 @@ publications: - topic: /fmu/out/collision_constraints type: px4_msgs::msg::CollisionConstraints + rate_limit: 50. - topic: /fmu/out/estimator_status_flags type: px4_msgs::msg::EstimatorStatusFlags + rate_limit: 5. - topic: /fmu/out/failsafe_flags type: px4_msgs::msg::FailsafeFlags + rate_limit: 5. - topic: /fmu/out/manual_control_setpoint type: px4_msgs::msg::ManualControlSetpoint + rate_limit: 25. - topic: /fmu/out/message_format_response type: px4_msgs::msg::MessageFormatResponse - topic: /fmu/out/position_setpoint_triplet type: px4_msgs::msg::PositionSetpointTriplet + rate_limit: 5. - topic: /fmu/out/sensor_combined type: px4_msgs::msg::SensorCombined - topic: /fmu/out/timesync_status type: px4_msgs::msg::TimesyncStatus + rate_limit: 10. # - topic: /fmu/out/vehicle_angular_velocity # type: px4_msgs::msg::VehicleAngularVelocity - topic: /fmu/out/vehicle_land_detected type: px4_msgs::msg::VehicleLandDetected + rate_limit: 5. - topic: /fmu/out/vehicle_attitude type: px4_msgs::msg::VehicleAttitude - topic: /fmu/out/vehicle_control_mode type: px4_msgs::msg::VehicleControlMode + rate_limit: 50. - topic: /fmu/out/vehicle_command_ack type: px4_msgs::msg::VehicleCommandAck - topic: /fmu/out/vehicle_global_position type: px4_msgs::msg::VehicleGlobalPosition + rate_limit: 50. - topic: /fmu/out/vehicle_gps_position type: px4_msgs::msg::SensorGps + rate_limit: 50. - topic: /fmu/out/vehicle_local_position type: px4_msgs::msg::VehicleLocalPosition + rate_limit: 50. - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus + rate_limit: 5. - topic: /fmu/out/airspeed_validated type: px4_msgs::msg::AirspeedValidated + rate_limit: 50. - topic: /fmu/out/vtol_vehicle_status type: px4_msgs::msg::VtolVehicleStatus - topic: /fmu/out/home_position type: px4_msgs::msg::HomePosition + rate_limit: 5. # Create uORB::Publication subscriptions: From 99f974e82e2c0e5268dea578e497c9c1408f575c Mon Sep 17 00:00:00 2001 From: GuillaumeLaine Date: Tue, 27 May 2025 17:35:46 +0200 Subject: [PATCH 084/130] docs: update uxrce_dds rate_limit example to reflect firmware values --- docs/en/middleware/uxrce_dds.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/en/middleware/uxrce_dds.md b/docs/en/middleware/uxrce_dds.md index c24b67fa1e..5af708102b 100644 --- a/docs/en/middleware/uxrce_dds.md +++ b/docs/en/middleware/uxrce_dds.md @@ -423,16 +423,17 @@ publications: - topic: /fmu/out/collision_constraints type: px4_msgs::msg::CollisionConstraints + rate_limit: 50. # Limit max publication rate to 50 Hz ... - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry - rate_limit: 150. + # Use default publication rate limit of 100 Hz - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus - rate_limit: 50. + rate_limit: 5. - topic: /fmu/out/vehicle_trajectory_waypoint_desired type: px4_msgs::msg::VehicleTrajectoryWaypoint From ed15258abb5c3ba7076138c212be82745f4e2a8f Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 19 May 2025 13:23:01 +0200 Subject: [PATCH 085/130] ICE: small cosmetic changes and make message definition clearer Signed-off-by: Silvan Fuhrer --- msg/InternalCombustionEngineControl.msg | 8 ++++---- .../InternalCombustionEngineControl.cpp | 11 +++++------ 2 files changed, 9 insertions(+), 10 deletions(-) diff --git a/msg/InternalCombustionEngineControl.msg b/msg/InternalCombustionEngineControl.msg index 08b4198e01..479b325e47 100644 --- a/msg/InternalCombustionEngineControl.msg +++ b/msg/InternalCombustionEngineControl.msg @@ -1,8 +1,8 @@ uint64 timestamp # time since system start (microseconds) -bool ignition_on # activate/deactivate ignition (Spark Plug) -float32 throttle_control # [0,1] - Motor should idle with 0. Includes slew rate if enabled. -float32 choke_control # [0,1] - 1 fully closes the air inlet. -float32 starter_engine_control # [0,1] - control value for electric starter motor. +bool ignition_on # activate/deactivate ignition (spark plug) +float32 throttle_control # setpoint for throttle actuator, with slew rate if enabled, idles with 0 [norm] [@range 0,1] +float32 choke_control # setpoint for choke actuator, 1: fully closed [norm] [@range 0,1] +float32 starter_engine_control # setpoint for (electric) starter motor [norm] [@range 0,1] uint8 user_request # user intent for the ICE being on/off diff --git a/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp b/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp index 1e8a1b1a35..eadd2aa46d 100644 --- a/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp +++ b/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp @@ -217,7 +217,6 @@ void InternalCombustionEngineControl::Run() case State::Fault: { - // do nothing if (user_request == UserOnOffRequest::Off) { _state = State::Stopped; _starting_retry_cycle = 0; @@ -355,7 +354,7 @@ int InternalCombustionEngineControl::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description - + The module controls internal combustion engine (ICE) features including: ignition (on/off), throttle and choke level, starter engine delay, and user request. @@ -389,18 +388,18 @@ The ICE is implemented with a (4) state machine: ![Architecture](../../assets/hardware/ice/ice_control_state_machine.png) The state machine: - + - Checks if [Rpm.msg](../msg_docs/Rpm.md) is updated to know if the engine is running - Allows for user inputs from: - - AUX{N} + - Manual control AUX - Arming state in [VehicleStatus.msg](../msg_docs/VehicleStatus.md) The module publishes [InternalCombustionEngineControl.msg](../msg_docs/InternalCombustionEngineControl.md). - + The architecture is as shown below: ![Architecture](../../assets/hardware/ice/ice_control_diagram.png) - + )DESCR_STR"); From cff5ecfd8889e77b718d370b3c8521aca768ace2 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 19 May 2025 13:23:45 +0200 Subject: [PATCH 086/130] ICE: allow throttle setpoint to be set to NAN to stop motor without disarming Signed-off-by: Silvan Fuhrer --- msg/InternalCombustionEngineControl.msg | 2 +- src/lib/mixer_module/functions/FunctionICEngineControl.hpp | 1 + .../InternalCombustionEngineControl.cpp | 5 ++++- 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/msg/InternalCombustionEngineControl.msg b/msg/InternalCombustionEngineControl.msg index 479b325e47..d1ea495998 100644 --- a/msg/InternalCombustionEngineControl.msg +++ b/msg/InternalCombustionEngineControl.msg @@ -1,7 +1,7 @@ uint64 timestamp # time since system start (microseconds) bool ignition_on # activate/deactivate ignition (spark plug) -float32 throttle_control # setpoint for throttle actuator, with slew rate if enabled, idles with 0 [norm] [@range 0,1] +float32 throttle_control # setpoint for throttle actuator, with slew rate if enabled, idles with 0 [norm] [@range 0,1] [@uncontrolled NAN to stop motor] float32 choke_control # setpoint for choke actuator, 1: fully closed [norm] [@range 0,1] float32 starter_engine_control # setpoint for (electric) starter motor [norm] [@range 0,1] diff --git a/src/lib/mixer_module/functions/FunctionICEngineControl.hpp b/src/lib/mixer_module/functions/FunctionICEngineControl.hpp index 0609f5cc94..6888384fce 100644 --- a/src/lib/mixer_module/functions/FunctionICEngineControl.hpp +++ b/src/lib/mixer_module/functions/FunctionICEngineControl.hpp @@ -55,6 +55,7 @@ public: internal_combustion_engine_control_s internal_combustion_engine_control; // map [0, 1] to [-1, 1] which is the interface for non-motor PWM channels + // NAN is mapped to disarmed if (_internal_combustion_engine_control_sub.update(&internal_combustion_engine_control)) { _data[0] = internal_combustion_engine_control.ignition_on * 2.f - 1.f; _data[1] = internal_combustion_engine_control.throttle_control * 2.f - 1.f; diff --git a/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp b/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp index eadd2aa46d..33ab49eb32 100644 --- a/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp +++ b/src/modules/internal_combustion_engine_control/InternalCombustionEngineControl.cpp @@ -291,7 +291,7 @@ void InternalCombustionEngineControl::controlEngineStop() _ignition_on = false; _choke_control = _param_ice_stop_choke.get() ? 1.f : 0.f; _starter_engine_control = 0.f; - _throttle_control = 0.f; + _throttle_control = NAN; // this will set it to the DISARMED value } void InternalCombustionEngineControl::controlEngineFault() @@ -393,6 +393,9 @@ The state machine: - Allows for user inputs from: - Manual control AUX - Arming state in [VehicleStatus.msg](../msg_docs/VehicleStatus.md) +- In the state "Stopped" the throttle is set to NAN, which by definition will set the + throttle output to the disarmed value configured for the specific output. + The module publishes [InternalCombustionEngineControl.msg](../msg_docs/InternalCombustionEngineControl.md). From 56d53b60c039c658f9afe343b34d2f053383df33 Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Thu, 15 May 2025 17:11:55 +0200 Subject: [PATCH 087/130] [bmp388] Initialize multiple times with delay --- src/drivers/barometer/bmp388/bmp388_i2c.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/drivers/barometer/bmp388/bmp388_i2c.cpp b/src/drivers/barometer/bmp388/bmp388_i2c.cpp index 73fe042705..8d47b8a09b 100644 --- a/src/drivers/barometer/bmp388/bmp388_i2c.cpp +++ b/src/drivers/barometer/bmp388/bmp388_i2c.cpp @@ -71,11 +71,20 @@ IBMP388 *bmp388_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency BMP388_I2C::BMP388_I2C(uint8_t bus, uint32_t device, int bus_frequency) : I2C(DRV_BARO_DEVTYPE_BMP388, MODULE_NAME, bus, device, bus_frequency) { + _retries = 1; } int BMP388_I2C::init() { - return I2C::init(); + for (int i = 0; i < 10; i++) { + if (I2C::init() == OK) { + return OK; + } + + px4_usleep(10000); + } + + return PX4_ERROR; } int BMP388_I2C::get_reg(uint8_t addr, uint8_t *value) From 3971db3cb4ac30fa2a2d2beff9308fe57149f47f Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Fri, 16 May 2025 14:08:14 +0200 Subject: [PATCH 088/130] [iis2mdc] Help device detection by retrying probing --- src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp b/src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp index c3cd02813c..79e165ca2c 100644 --- a/src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp +++ b/src/drivers/magnetometer/st/iis2mdc/iis2mdc_i2c.cpp @@ -50,6 +50,7 @@ protected: IIS2MDC_I2C::IIS2MDC_I2C(const I2CSPIDriverConfig &config) : I2C(config) { + _retries = 10; } int IIS2MDC_I2C::probe() From f0b05ea7cfd9de4113f4cd63e8068cf8089bc158 Mon Sep 17 00:00:00 2001 From: Silvan Date: Mon, 2 Jun 2025 14:24:43 +0200 Subject: [PATCH 089/130] ControlAllocator: only use torque, not thrust sp as callback item Signed-off-by: Silvan --- src/modules/control_allocator/ControlAllocator.cpp | 6 ------ src/modules/control_allocator/ControlAllocator.hpp | 2 +- 2 files changed, 1 insertion(+), 7 deletions(-) diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index 99e280dd71..c3950aed4f 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -95,11 +95,6 @@ ControlAllocator::init() return false; } - if (!_vehicle_thrust_setpoint_sub.registerCallback()) { - PX4_ERR("callback registration failed"); - return false; - } - #ifndef ENABLE_LOCKSTEP_SCHEDULER // Backup schedule would interfere with lockstep ScheduleDelayed(50_ms); #endif @@ -309,7 +304,6 @@ ControlAllocator::Run() { if (should_exit()) { _vehicle_torque_setpoint_sub.unregisterCallback(); - _vehicle_thrust_setpoint_sub.unregisterCallback(); exit_and_cleanup(); return; } diff --git a/src/modules/control_allocator/ControlAllocator.hpp b/src/modules/control_allocator/ControlAllocator.hpp index 1f91f7d17d..ce92c5036b 100644 --- a/src/modules/control_allocator/ControlAllocator.hpp +++ b/src/modules/control_allocator/ControlAllocator.hpp @@ -175,7 +175,7 @@ private: // Inputs uORB::SubscriptionCallbackWorkItem _vehicle_torque_setpoint_sub{this, ORB_ID(vehicle_torque_setpoint)}; /**< vehicle torque setpoint subscription */ - uORB::SubscriptionCallbackWorkItem _vehicle_thrust_setpoint_sub{this, ORB_ID(vehicle_thrust_setpoint)}; /**< vehicle thrust setpoint subscription */ + uORB::Subscription _vehicle_thrust_setpoint_sub{ORB_ID(vehicle_thrust_setpoint)}; /**< vehicle thrust setpoint subscription */ uORB::Subscription _vehicle_torque_setpoint1_sub{ORB_ID(vehicle_torque_setpoint), 1}; /**< vehicle torque setpoint subscription (2. instance) */ uORB::Subscription _vehicle_thrust_setpoint1_sub{ORB_ID(vehicle_thrust_setpoint), 1}; /**< vehicle thrust setpoint subscription (2. instance) */ From 66fe3aa2b3a01a6608567aab835e057844d2770a Mon Sep 17 00:00:00 2001 From: Silvan Date: Mon, 2 Jun 2025 14:25:54 +0200 Subject: [PATCH 090/130] ControlAllocator: only run allocator on torque updates, not thrust Signed-off-by: Silvan --- src/modules/control_allocator/ControlAllocator.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index c3950aed4f..a7e43a64e3 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -390,15 +390,8 @@ ControlAllocator::Run() } - // Also run allocator on thrust setpoint changes if the torque setpoint - // has not been updated for more than 5ms if (_vehicle_thrust_setpoint_sub.update(&vehicle_thrust_setpoint)) { _thrust_sp = matrix::Vector3f(vehicle_thrust_setpoint.xyz); - - if (dt > 0.005f) { - do_update = true; - _timestamp_sample = vehicle_thrust_setpoint.timestamp_sample; - } } if (do_update) { From 5332010b13d7cd9f1c6b5a4cda420bbd13e05763 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 21 May 2025 15:20:29 +0200 Subject: [PATCH 091/130] ekf2: move on ground GNSS checks to separate function --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 172 +++++++++--------- src/modules/ekf2/EKF/ekf.h | 1 + src/modules/ekf2/EKF/estimator_interface.h | 4 +- 3 files changed, 91 insertions(+), 86 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp index 81b3fcc76b..cf28524c79 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -55,112 +55,41 @@ #define MASK_GPS_VSPD (1<<8) #define MASK_GPS_SPOOFED (1<<9) -bool Ekf::runGnssChecks(const gnssSample &gps) +bool Ekf::runGnssChecks(const gnssSample &gnss) { - _gps_check_fail_status.flags.spoofed = gps.spoofed; + _gps_check_fail_status.flags.spoofed = gnss.spoofed; // Check the fix type - _gps_check_fail_status.flags.fix = (gps.fix_type < 3); + _gps_check_fail_status.flags.fix = (gnss.fix_type < 3); // Check the number of satellites - _gps_check_fail_status.flags.nsats = (gps.nsats < _params.req_nsats); + _gps_check_fail_status.flags.nsats = (gnss.nsats < _params.req_nsats); // Check the position dilution of precision - _gps_check_fail_status.flags.pdop = (gps.pdop > _params.req_pdop); + _gps_check_fail_status.flags.pdop = (gnss.pdop > _params.req_pdop); // Check the reported horizontal and vertical position accuracy - _gps_check_fail_status.flags.hacc = (gps.hacc > _params.req_hacc); - _gps_check_fail_status.flags.vacc = (gps.vacc > _params.req_vacc); + _gps_check_fail_status.flags.hacc = (gnss.hacc > _params.req_hacc); + _gps_check_fail_status.flags.vacc = (gnss.vacc > _params.req_vacc); // Check the reported speed accuracy - _gps_check_fail_status.flags.sacc = (gps.sacc > _params.req_sacc); + _gps_check_fail_status.flags.sacc = (gnss.sacc > _params.req_sacc); - // Calculate time lapsed since last update, limit to prevent numerical errors and calculate a lowpass filter coefficient - constexpr float filt_time_const = 10.0f; - const float dt = math::constrain(float(int64_t(gps.time_us) - int64_t(_gps_pos_prev.getProjectionReferenceTimestamp())) - * 1e-6f, 0.001f, filt_time_const); - const float filter_coef = dt / filt_time_const; - - // The following checks are only valid when the vehicle is at rest - const double lat = gps.lat; - const double lon = gps.lon; - - if (!_control_status.flags.in_air && _control_status.flags.vehicle_at_rest) { - // Calculate position movement since last measurement - float delta_pos_n = 0.0f; - float delta_pos_e = 0.0f; - - // calculate position movement since last GPS fix - if (_gps_pos_prev.getProjectionReferenceTimestamp() > 0) { - _gps_pos_prev.project(lat, lon, delta_pos_n, delta_pos_e); - - } else { - // no previous position has been set - _gps_pos_prev.initReference(lat, lon, gps.time_us); - _gps_alt_prev = gps.alt; - } - - // Calculate the horizontal and vertical drift velocity components and limit to 10x the threshold - const Vector3f vel_limit(_params.req_hdrift, _params.req_hdrift, _params.req_vdrift); - Vector3f delta_pos(delta_pos_n, delta_pos_e, (_gps_alt_prev - gps.alt)); - - // Apply a low pass filter - _gps_pos_deriv_filt = delta_pos / dt * filter_coef + _gps_pos_deriv_filt * (1.0f - filter_coef); - - // Apply anti-windup to the state instead of the input to avoid generating a bias on asymmetric signals - _gps_pos_deriv_filt = matrix::constrain(_gps_pos_deriv_filt, -10.0f * vel_limit, 10.0f * vel_limit); - - // hdrift: calculate the horizontal drift speed and fail if too high - _gps_horizontal_position_drift_rate_m_s = Vector2f(_gps_pos_deriv_filt.xy()).norm(); - _gps_check_fail_status.flags.hdrift = (_gps_horizontal_position_drift_rate_m_s > _params.req_hdrift); - - // vdrift: fail if the vertical drift speed is too high - _gps_vertical_position_drift_rate_m_s = fabsf(_gps_pos_deriv_filt(2)); - _gps_check_fail_status.flags.vdrift = (_gps_vertical_position_drift_rate_m_s > _params.req_vdrift); - - // hspeed: check the magnitude of the filtered horizontal GNSS velocity - const Vector2f gps_velNE = matrix::constrain(Vector2f(gps.vel.xy()), - -10.0f * _params.req_hdrift, - 10.0f * _params.req_hdrift); - _gps_velNE_filt = gps_velNE * filter_coef + _gps_velNE_filt * (1.0f - filter_coef); - _gps_filtered_horizontal_velocity_m_s = _gps_velNE_filt.norm(); - _gps_check_fail_status.flags.hspeed = (_gps_filtered_horizontal_velocity_m_s > _params.req_hdrift); - - // vspeed: check the magnitude of the filtered vertical GNSS velocity - const float gnss_vz_limit = 10.f * _params.req_vdrift; - const float gnss_vz = math::constrain(gps.vel(2), -gnss_vz_limit, gnss_vz_limit); - _gps_vel_d_filt = gnss_vz * filter_coef + _gps_vel_d_filt * (1.f - filter_coef); - - _gps_check_fail_status.flags.vspeed = (fabsf(_gps_vel_d_filt) > _params.req_vdrift); - - } else if (_control_status.flags.in_air) { - // These checks are always declared as passed when flying - // If on ground and moving, the last result before movement commenced is kept - _gps_check_fail_status.flags.hdrift = false; - _gps_check_fail_status.flags.vdrift = false; - _gps_check_fail_status.flags.hspeed = false; - _gps_check_fail_status.flags.vspeed = false; - - resetGpsDriftCheckFilters(); - - } else { - // This is the case where the vehicle is on ground and IMU movement is blocking the drift calculation - resetGpsDriftCheckFilters(); - } + runOnGroundGnssChecks(gnss); // force horizontal speed failure if above the limit - if (gps.vel.xy().longerThan(_params.velocity_limit)) { + if (gnss.vel.xy().longerThan(_params.velocity_limit)) { _gps_check_fail_status.flags.hspeed = true; } // force vertical speed failure if above the limit - if (fabsf(gps.vel(2)) > _params.velocity_limit) { + if (fabsf(gnss.vel(2)) > _params.velocity_limit) { _gps_check_fail_status.flags.vspeed = true; } // save GPS fix for next time - _gps_pos_prev.initReference(lat, lon, gps.time_us); - _gps_alt_prev = gps.alt; + _gnss_pos_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); + _gnss_alt_prev = gnss.alt; // assume failed first time through if (_last_gps_fail_us == 0) { @@ -190,6 +119,81 @@ bool Ekf::runGnssChecks(const gnssSample &gps) } } +void Ekf::runOnGroundGnssChecks(const gnssSample &gnss) +{ + if (_control_status.flags.in_air) { + // These checks are always declared as passed when flying + // If on ground and moving, the last result before movement commenced is kept + _gps_check_fail_status.flags.hdrift = false; + _gps_check_fail_status.flags.vdrift = false; + _gps_check_fail_status.flags.hspeed = false; + _gps_check_fail_status.flags.vspeed = false; + + resetGpsDriftCheckFilters(); + return; + } + + if (_control_status.flags.vehicle_at_rest) { + // Calculate time lapsed since last update, limit to prevent numerical errors and calculate a lowpass filter coefficient + constexpr float filt_time_const = 10.0f; + const float dt = math::constrain(float(int64_t(gnss.time_us) - int64_t( + _gnss_pos_prev.getProjectionReferenceTimestamp())) + * 1e-6f, 0.001f, filt_time_const); + const float filter_coef = dt / filt_time_const; + + // Calculate position movement since last measurement + float delta_pos_n = 0.0f; + float delta_pos_e = 0.0f; + + // calculate position movement since last GPS fix + if (_gnss_pos_prev.getProjectionReferenceTimestamp() > 0) { + _gnss_pos_prev.project(gnss.lat, gnss.lon, delta_pos_n, delta_pos_e); + + } else { + // no previous position has been set + _gnss_pos_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); + _gnss_alt_prev = gnss.alt; + } + + // Calculate the horizontal and vertical drift velocity components and limit to 10x the threshold + const Vector3f vel_limit(_params.req_hdrift, _params.req_hdrift, _params.req_vdrift); + Vector3f delta_pos(delta_pos_n, delta_pos_e, (_gnss_alt_prev - gnss.alt)); + + // Apply a low pass filter + _gps_pos_deriv_filt = delta_pos / dt * filter_coef + _gps_pos_deriv_filt * (1.0f - filter_coef); + + // Apply anti-windup to the state instead of the input to avoid generating a bias on asymmetric signals + _gps_pos_deriv_filt = matrix::constrain(_gps_pos_deriv_filt, -10.0f * vel_limit, 10.0f * vel_limit); + + // hdrift: calculate the horizontal drift speed and fail if too high + _gps_horizontal_position_drift_rate_m_s = Vector2f(_gps_pos_deriv_filt.xy()).norm(); + _gps_check_fail_status.flags.hdrift = (_gps_horizontal_position_drift_rate_m_s > _params.req_hdrift); + + // vdrift: fail if the vertical drift speed is too high + _gps_vertical_position_drift_rate_m_s = fabsf(_gps_pos_deriv_filt(2)); + _gps_check_fail_status.flags.vdrift = (_gps_vertical_position_drift_rate_m_s > _params.req_vdrift); + + // hspeed: check the magnitude of the filtered horizontal GNSS velocity + const Vector2f gps_velNE = matrix::constrain(Vector2f(gnss.vel.xy()), + -10.0f * _params.req_hdrift, + 10.0f * _params.req_hdrift); + _gps_velNE_filt = gps_velNE * filter_coef + _gps_velNE_filt * (1.0f - filter_coef); + _gps_filtered_horizontal_velocity_m_s = _gps_velNE_filt.norm(); + _gps_check_fail_status.flags.hspeed = (_gps_filtered_horizontal_velocity_m_s > _params.req_hdrift); + + // vspeed: check the magnitude of the filtered vertical GNSS velocity + const float gnss_vz_limit = 10.f * _params.req_vdrift; + const float gnss_vz = math::constrain(gnss.vel(2), -gnss_vz_limit, gnss_vz_limit); + _gps_vel_d_filt = gnss_vz * filter_coef + _gps_vel_d_filt * (1.f - filter_coef); + + _gps_check_fail_status.flags.vspeed = (fabsf(_gps_vel_d_filt) > _params.req_vdrift); + + } else { + // This is the case where the vehicle is on ground and IMU movement is blocking the drift calculation + resetGpsDriftCheckFilters(); + } +} + void Ekf::resetGpsDriftCheckFilters() { _gps_velNE_filt.setZero(); diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 1dad06d304..8f40beae2a 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -883,6 +883,7 @@ private: * Checks are adjusted using the EKF2_REQ_* parameters */ bool runGnssChecks(const gnssSample &gps); + void runOnGroundGnssChecks(const gnssSample &gnss); void controlGnssHeightFusion(const gnssSample &gps_sample); void stopGpsHgtFusion(); diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 592b786a6e..10c1832c67 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -402,8 +402,8 @@ protected: float _gps_vertical_position_drift_rate_m_s{NAN}; // Vertical position drift rate (m/s) float _gps_filtered_horizontal_velocity_m_s{NAN}; // Filtered horizontal velocity (m/s) - MapProjection _gps_pos_prev{}; // Contains WGS-84 position latitude and longitude of the previous GPS message - float _gps_alt_prev{0.0f}; // height from the previous GPS message (m) + MapProjection _gnss_pos_prev{}; // Contains WGS-84 position latitude and longitude of the previous GPS message + float _gnss_alt_prev{0.0f}; // height from the previous GPS message (m) # if defined(CONFIG_EKF2_GNSS_YAW) // innovation consistency check monitoring ratios From 2dbce4d958b26b030a983fbc47b35e3b4cd49f20 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 21 May 2025 15:56:40 +0200 Subject: [PATCH 092/130] ekf2: replace defines with enum class --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 35 ++++++++----------- src/modules/ekf2/EKF/ekf.h | 15 ++++++++ 2 files changed, 29 insertions(+), 21 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp index cf28524c79..c1e37e0893 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -43,17 +43,10 @@ #include -// GPS pre-flight check bit locations -#define MASK_GPS_NSATS (1<<0) -#define MASK_GPS_PDOP (1<<1) -#define MASK_GPS_HACC (1<<2) -#define MASK_GPS_VACC (1<<3) -#define MASK_GPS_SACC (1<<4) -#define MASK_GPS_HDRIFT (1<<5) -#define MASK_GPS_VDRIFT (1<<6) -#define MASK_GPS_HSPD (1<<7) -#define MASK_GPS_VSPD (1<<8) -#define MASK_GPS_SPOOFED (1<<9) +bool Ekf::isGnssCheckEnabled(GnssChecksMask check) +{ + return (_params.gps_check_mask & static_cast(check)); +} bool Ekf::runGnssChecks(const gnssSample &gnss) { @@ -99,16 +92,16 @@ bool Ekf::runGnssChecks(const gnssSample &gnss) // if any user selected checks have failed, record the fail time if ( _gps_check_fail_status.flags.fix || - (_gps_check_fail_status.flags.nsats && (_params.gps_check_mask & MASK_GPS_NSATS)) || - (_gps_check_fail_status.flags.pdop && (_params.gps_check_mask & MASK_GPS_PDOP)) || - (_gps_check_fail_status.flags.hacc && (_params.gps_check_mask & MASK_GPS_HACC)) || - (_gps_check_fail_status.flags.vacc && (_params.gps_check_mask & MASK_GPS_VACC)) || - (_gps_check_fail_status.flags.sacc && (_params.gps_check_mask & MASK_GPS_SACC)) || - (_gps_check_fail_status.flags.hdrift && (_params.gps_check_mask & MASK_GPS_HDRIFT)) || - (_gps_check_fail_status.flags.vdrift && (_params.gps_check_mask & MASK_GPS_VDRIFT)) || - (_gps_check_fail_status.flags.hspeed && (_params.gps_check_mask & MASK_GPS_HSPD)) || - (_gps_check_fail_status.flags.vspeed && (_params.gps_check_mask & MASK_GPS_VSPD)) || - (_gps_check_fail_status.flags.spoofed && (_params.gps_check_mask & MASK_GPS_SPOOFED)) + (_gps_check_fail_status.flags.nsats && isGnssCheckEnabled(GnssChecksMask::kNsats)) || + (_gps_check_fail_status.flags.pdop && isGnssCheckEnabled(GnssChecksMask::kPdop)) || + (_gps_check_fail_status.flags.hacc && isGnssCheckEnabled(GnssChecksMask::kHacc)) || + (_gps_check_fail_status.flags.vacc && isGnssCheckEnabled(GnssChecksMask::kVacc)) || + (_gps_check_fail_status.flags.sacc && isGnssCheckEnabled(GnssChecksMask::kSacc)) || + (_gps_check_fail_status.flags.hdrift && isGnssCheckEnabled(GnssChecksMask::kHdrift)) || + (_gps_check_fail_status.flags.vdrift && isGnssCheckEnabled(GnssChecksMask::kVdrift)) || + (_gps_check_fail_status.flags.hspeed && isGnssCheckEnabled(GnssChecksMask::kHspd)) || + (_gps_check_fail_status.flags.vspeed && isGnssCheckEnabled(GnssChecksMask::kVspd)) || + (_gps_check_fail_status.flags.spoofed && isGnssCheckEnabled(GnssChecksMask::kSpoofed)) ) { _last_gps_fail_us = _time_delayed_us; return false; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 8f40beae2a..dc5a40d707 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -883,6 +883,21 @@ private: * Checks are adjusted using the EKF2_REQ_* parameters */ bool runGnssChecks(const gnssSample &gps); + + enum class GnssChecksMask : int32_t { + kNsats = (1 << 0), + kPdop = (1 << 1), + kHacc = (1 << 2), + kVacc = (1 << 3), + kSacc = (1 << 4), + kHdrift = (1 << 5), + kVdrift = (1 << 6), + kHspd = (1 << 7), + kVspd = (1 << 8), + kSpoofed = (1 << 9) + }; + + bool isGnssCheckEnabled(GnssChecksMask check); void runOnGroundGnssChecks(const gnssSample &gnss); void controlGnssHeightFusion(const gnssSample &gps_sample); From c33d79cfb4ec433025a08074d959790c6b8789af Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 23 May 2025 09:32:11 +0200 Subject: [PATCH 093/130] ekf2: move gnss_checks to their own class --- src/modules/ekf2/CMakeLists.txt | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 2 +- .../gnss/{gps_checks.cpp => gnss_checks.cpp} | 83 +++++---- .../ekf2/EKF/aid_sources/gnss/gnss_checks.hpp | 165 ++++++++++++++++++ .../aid_sources/gnss/gnss_height_control.cpp | 2 +- .../EKF/aid_sources/gnss/gnss_yaw_control.cpp | 2 +- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 34 ++-- src/modules/ekf2/EKF/common.h | 18 -- src/modules/ekf2/EKF/ekf.cpp | 3 +- src/modules/ekf2/EKF/ekf.h | 43 +---- src/modules/ekf2/EKF/estimator_interface.h | 28 ++- 11 files changed, 261 insertions(+), 121 deletions(-) rename src/modules/ekf2/EKF/aid_sources/gnss/{gps_checks.cpp => gnss_checks.cpp} (86%) create mode 100644 src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 181978792c..a7b8e18f8a 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -173,8 +173,8 @@ endif() if(CONFIG_EKF2_GNSS) list(APPEND EKF_SRCS + EKF/aid_sources/gnss/gnss_checks.cpp EKF/aid_sources/gnss/gnss_height_control.cpp - EKF/aid_sources/gnss/gps_checks.cpp EKF/aid_sources/gnss/gps_control.cpp ) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 2c4c898d41..381e265380 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -90,8 +90,8 @@ endif() if(CONFIG_EKF2_GNSS) list(APPEND EKF_SRCS + aid_sources/gnss/gnss_checks.cpp aid_sources/gnss/gnss_height_control.cpp - aid_sources/gnss/gps_checks.cpp aid_sources/gnss/gps_control.cpp ) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp similarity index 86% rename from src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp rename to src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp index c1e37e0893..cf216b5c65 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2015-2023 PX4 Development Team. All rights reserved. + * Copyright (c) 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -32,26 +32,56 @@ ****************************************************************************/ /** - * @file gps_checks.cpp - * Perform pre-flight and in-flight GPS quality checks - * - * @author Paul Riseborough - * + * @file gnss_checks.cpp + * Perform pre-flight and in-flight GNSS quality checks */ -#include "ekf.h" +#include "aid_sources/gnss/gnss_checks.hpp" -#include - -bool Ekf::isGnssCheckEnabled(GnssChecksMask check) +namespace estimator { - return (_params.gps_check_mask & static_cast(check)); +bool GnssChecks::runGnssChecks(const gnssSample &gnss, uint64_t time_us) +{ + // assume failed first time through + if (_last_gps_fail_us == 0) { + _last_gps_fail_us = time_us; + } + + bool passed = false; + + if (_initial_checks_passed) { + if (runInitialFixChecks(gnss)) { + _last_gps_pass_us = time_us; + passed = isTimedOut(_last_gps_fail_us, time_us, math::max((uint64_t)1e6, (uint64_t)_min_gps_health_time_us / 10)); + + } else { + _last_gps_fail_us = time_us; + } + + } else { + if (runInitialFixChecks(gnss)) { + _last_gps_pass_us = time_us; + + if (isTimedOut(_last_gps_fail_us, time_us, (uint64_t)_min_gps_health_time_us)) { + _initial_checks_passed = true; + passed = true; + } + + } else { + _last_gps_fail_us = time_us; + } + } + + // save GPS fix for next time + _gnss_pos_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); + _gnss_alt_prev = gnss.alt; + + _checks_passed = passed; + return passed; } -bool Ekf::runGnssChecks(const gnssSample &gnss) +bool GnssChecks::runInitialFixChecks(const gnssSample &gnss) { - _gps_check_fail_status.flags.spoofed = gnss.spoofed; - // Check the fix type _gps_check_fail_status.flags.fix = (gnss.fix_type < 3); @@ -68,6 +98,8 @@ bool Ekf::runGnssChecks(const gnssSample &gnss) // Check the reported speed accuracy _gps_check_fail_status.flags.sacc = (gnss.sacc > _params.req_sacc); + _gps_check_fail_status.flags.spoofed = gnss.spoofed; + runOnGroundGnssChecks(gnss); // force horizontal speed failure if above the limit @@ -80,14 +112,7 @@ bool Ekf::runGnssChecks(const gnssSample &gnss) _gps_check_fail_status.flags.vspeed = true; } - // save GPS fix for next time - _gnss_pos_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); - _gnss_alt_prev = gnss.alt; - - // assume failed first time through - if (_last_gps_fail_us == 0) { - _last_gps_fail_us = _time_delayed_us; - } + bool passed = true; // if any user selected checks have failed, record the fail time if ( @@ -103,16 +128,13 @@ bool Ekf::runGnssChecks(const gnssSample &gnss) (_gps_check_fail_status.flags.vspeed && isGnssCheckEnabled(GnssChecksMask::kVspd)) || (_gps_check_fail_status.flags.spoofed && isGnssCheckEnabled(GnssChecksMask::kSpoofed)) ) { - _last_gps_fail_us = _time_delayed_us; - return false; - - } else { - _last_gps_pass_us = _time_delayed_us; - return true; + passed = false; } + + return passed; } -void Ekf::runOnGroundGnssChecks(const gnssSample &gnss) +void GnssChecks::runOnGroundGnssChecks(const gnssSample &gnss) { if (_control_status.flags.in_air) { // These checks are always declared as passed when flying @@ -187,7 +209,7 @@ void Ekf::runOnGroundGnssChecks(const gnssSample &gnss) } } -void Ekf::resetGpsDriftCheckFilters() +void GnssChecks::resetGpsDriftCheckFilters() { _gps_velNE_filt.setZero(); _gps_vel_d_filt = 0.f; @@ -198,3 +220,4 @@ void Ekf::resetGpsDriftCheckFilters() _gps_vertical_position_drift_rate_m_s = NAN; _gps_filtered_horizontal_velocity_m_s = NAN; } +}; // namespace estimator diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp new file mode 100644 index 0000000000..fa8ac7d2d4 --- /dev/null +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp @@ -0,0 +1,165 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef EKF_GNSS_CHECKS_H +#define EKF_GNSS_CHECKS_H + +#include + +#include "../../common.h" + +namespace estimator +{ +class GnssChecks final +{ +public: + GnssChecks(int32_t &check_mask, int32_t &req_nsats, float &req_pdop, float &req_hacc, float &req_vacc, float &req_sacc, + float &req_hdrift, float &req_vdrift, float &velocity_limit, uint32_t &min_health_time_us, + filter_control_status_u &control_status): + _params{check_mask, req_nsats, req_pdop, req_hacc, req_vacc, req_sacc, req_hdrift, req_vdrift, velocity_limit}, + _min_gps_health_time_us(min_health_time_us), + _control_status(control_status) + {}; + + union gps_check_fail_status_u { + struct { + uint16_t fix : 1; ///< 0 - true if the fix type is insufficient (no 3D solution) + uint16_t nsats : 1; ///< 1 - true if number of satellites used is insufficient + uint16_t pdop : 1; ///< 2 - true if position dilution of precision is insufficient + uint16_t hacc : 1; ///< 3 - true if reported horizontal accuracy is insufficient + uint16_t vacc : 1; ///< 4 - true if reported vertical accuracy is insufficient + uint16_t sacc : 1; ///< 5 - true if reported speed accuracy is insufficient + uint16_t hdrift : 1; ///< 6 - true if horizontal drift is excessive (can only be used when stationary on ground) + uint16_t vdrift : 1; ///< 7 - true if vertical drift is excessive (can only be used when stationary on ground) + uint16_t hspeed : 1; ///< 8 - true if horizontal speed is excessive (can only be used when stationary on ground) + uint16_t vspeed : 1; ///< 9 - true if vertical speed error is excessive + uint16_t spoofed: 1; ///< 10 - true if the GNSS data is spoofed + } flags; + uint16_t value; + }; + + void resetHard() + { + _initial_checks_passed = false; + reset(); + } + + void reset() + { + _checks_passed = false; + _last_gps_pass_us = 0; + _last_gps_fail_us = 0; + resetGpsDriftCheckFilters(); + } + + /* + * Return true if the GPS solution quality is adequate. + * Checks are activated using the EKF2_GPS_CHECK bitmask parameter + * Checks are adjusted using the EKF2_REQ_* parameters + */ + bool runGnssChecks(const gnssSample &gps, uint64_t time_us); + bool passed() const { return _checks_passed; } + bool initialChecksPassed() const { return _initial_checks_passed; } + uint64_t getLastPassUs() const { return _last_gps_pass_us; } + uint64_t getLastFailUs() const { return _last_gps_fail_us; } + + const gps_check_fail_status_u &getFailStatus() const { return _gps_check_fail_status; } + + float horizontal_position_drift_rate_m_s() const { return _gps_horizontal_position_drift_rate_m_s; } + float vertical_position_drift_rate_m_s() const { return _gps_vertical_position_drift_rate_m_s; } + float filtered_horizontal_velocity_m_s() const { return _gps_filtered_horizontal_velocity_m_s; } + +private: + enum class GnssChecksMask : int32_t { + kNsats = (1 << 0), + kPdop = (1 << 1), + kHacc = (1 << 2), + kVacc = (1 << 3), + kSacc = (1 << 4), + kHdrift = (1 << 5), + kVdrift = (1 << 6), + kHspd = (1 << 7), + kVspd = (1 << 8), + kSpoofed = (1 << 9) + }; + + bool isGnssCheckEnabled(GnssChecksMask check) { return (_params.check_mask & static_cast(check)); } + + bool runInitialFixChecks(const gnssSample &gnss); + void runOnGroundGnssChecks(const gnssSample &gnss); + + void resetGpsDriftCheckFilters(); + + bool isTimedOut(uint64_t timestamp_to_check_us, uint64_t now_us, uint64_t timeout_period) const + { + return (timestamp_to_check_us == 0) || (timestamp_to_check_us + timeout_period < now_us); + } + + gps_check_fail_status_u _gps_check_fail_status{}; + + float _gps_horizontal_position_drift_rate_m_s{NAN}; // Horizontal position drift rate (m/s) + float _gps_vertical_position_drift_rate_m_s{NAN}; // Vertical position drift rate (m/s) + float _gps_filtered_horizontal_velocity_m_s{NAN}; // Filtered horizontal velocity (m/s) + + MapProjection _gnss_pos_prev{}; // Contains WGS-84 position latitude and longitude of the previous GPS message + float _gnss_alt_prev{0.0f}; // height from the previous GPS message (m) + + // variables used for the GPS quality checks + Vector3f _gps_pos_deriv_filt{}; + Vector2f _gps_velNE_filt{}; ///< filtered GPS North and East velocity (m/sec) + + float _gps_vel_d_filt{0.0f}; ///< GNSS filtered Down velocity (m/sec) + uint64_t _last_gps_fail_us{0}; + uint64_t _last_gps_pass_us{0}; + bool _initial_checks_passed{false}; + bool _checks_passed{false}; + + struct Params { + const int32_t &check_mask; + const int32_t &req_nsats; + const float &req_pdop; + const float &req_hacc; + const float &req_vacc; + const float &req_sacc; + const float &req_hdrift; + const float &req_vdrift; + const float &velocity_limit; + }; + + const Params _params; + const uint32_t &_min_gps_health_time_us; ///< GPS is marked as healthy only after this amount of time + const filter_control_status_u &_control_status; +}; +}; // namespace estimator + +#endif // !EKF_GNSS_CHECKS_H diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index 9426fa2664..e8285f7267 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -87,7 +87,7 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) // determine if we should use height aiding const bool common_conditions_passing = measurement_valid && _local_origin_lat_lon.isInitialized() - && _gps_checks_passed; + && _gnss_checks.passed(); const bool continuing_conditions_passing = (_params.gnss_ctrl & static_cast(GnssCtrl::VPOS)) && common_conditions_passing; diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_yaw_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_yaw_control.cpp index bd37c0fb37..06b8fffccc 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_yaw_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_yaw_control.cpp @@ -66,7 +66,7 @@ void Ekf::controlGnssYawFusion(const gnssSample &gnss_sample) 2 * GNSS_YAW_MAX_INTERVAL); const bool starting_conditions_passing = continuing_conditions_passing - && _gps_checks_passed + && _gnss_checks.passed() && !is_gnss_yaw_data_intermittent && !_gps_intermittent; diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index 9eabfe156d..2373c76481 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -63,23 +63,22 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) if (_gps_data_ready) { const gnssSample &gnss_sample = _gps_sample_delayed; - if (runGnssChecks(gnss_sample) - && isTimedOut(_last_gps_fail_us, max((uint64_t)1e6, (uint64_t)_min_gps_health_time_us / 10))) { - if (isTimedOut(_last_gps_fail_us, (uint64_t)_min_gps_health_time_us)) { - // First time checks are passing, latching. - if (!_gps_checks_passed) { - _information_events.flags.gps_checks_passed = true; - } + const bool initial_checks_passed_prev = _gnss_checks.initialChecksPassed(); - _gps_checks_passed = true; + if (_gnss_checks.runGnssChecks(gnss_sample, _time_delayed_us)) { + if (_gnss_checks.initialChecksPassed() && !initial_checks_passed_prev) { + // First time checks are passing, latching. + _information_events.flags.gps_checks_passed = true; } } else { // Skip this sample _gps_data_ready = false; - if ((_control_status.flags.gnss_vel || _control_status.flags.gnss_pos) - && isTimedOut(_last_gps_pass_us, _params.reset_timeout_max)) { + const bool using_gnss = _control_status.flags.gnss_vel || _control_status.flags.gnss_pos; + const bool gnss_checks_pass_timeout = isTimedOut(_gnss_checks.getLastPassUs(), _params.reset_timeout_max); + + if (using_gnss && gnss_checks_pass_timeout) { stopGnssFusion(); ECL_WARN("GNSS quality poor - stopping use"); } @@ -128,7 +127,7 @@ void Ekf::controlGnssVelFusion(estimator_aid_source3d_s &aid_src, const bool for const bool continuing_conditions_passing = (_params.gnss_ctrl & static_cast(GnssCtrl::VEL)) && _control_status.flags.tilt_align && _control_status.flags.yaw_align; - const bool starting_conditions_passing = continuing_conditions_passing && _gps_checks_passed; + const bool starting_conditions_passing = continuing_conditions_passing && _gnss_checks.passed(); if (_control_status.flags.gnss_vel) { if (continuing_conditions_passing) { @@ -175,8 +174,8 @@ void Ekf::controlGnssPosFusion(estimator_aid_source2d_s &aid_src, const bool for const bool continuing_conditions_passing = gnss_pos_enabled && _control_status.flags.tilt_align && _control_status.flags.yaw_align; - const bool starting_conditions_passing = continuing_conditions_passing && _gps_checks_passed; - const bool gpos_init_conditions_passing = gnss_pos_enabled && _gps_checks_passed; + const bool starting_conditions_passing = continuing_conditions_passing && _gnss_checks.passed(); + const bool gpos_init_conditions_passing = gnss_pos_enabled && _gnss_checks.passed(); if (_control_status.flags.gnss_pos) { if (continuing_conditions_passing) { @@ -394,8 +393,7 @@ bool Ekf::shouldResetGpsFusion() const void Ekf::stopGnssFusion() { if (_control_status.flags.gnss_vel || _control_status.flags.gnss_pos) { - _last_gps_fail_us = 0; - _last_gps_pass_us = 0; + _gnss_checks.reset(); } stopGnssVelFusion(); @@ -416,8 +414,7 @@ void Ekf::stopGnssVelFusion() //TODO: what if gnss yaw or height is used? if (!_control_status.flags.gnss_pos) { - _last_gps_fail_us = 0; - _last_gps_pass_us = 0; + _gnss_checks.reset(); } } } @@ -430,8 +427,7 @@ void Ekf::stopGnssPosFusion() //TODO: what if gnss yaw or height is used? if (!_control_status.flags.gnss_vel) { - _last_gps_fail_us = 0; - _last_gps_pass_us = 0; + _gnss_checks.reset(); } } } diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 5ec5e42925..8ee95dea82 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -543,24 +543,6 @@ union innovation_fault_status_u { uint16_t value; }; -// publish the status of various GPS quality checks -union gps_check_fail_status_u { - struct { - uint16_t fix : 1; ///< 0 - true if the fix type is insufficient (no 3D solution) - uint16_t nsats : 1; ///< 1 - true if number of satellites used is insufficient - uint16_t pdop : 1; ///< 2 - true if position dilution of precision is insufficient - uint16_t hacc : 1; ///< 3 - true if reported horizontal accuracy is insufficient - uint16_t vacc : 1; ///< 4 - true if reported vertical accuracy is insufficient - uint16_t sacc : 1; ///< 5 - true if reported speed accuracy is insufficient - uint16_t hdrift : 1; ///< 6 - true if horizontal drift is excessive (can only be used when stationary on ground) - uint16_t vdrift : 1; ///< 7 - true if vertical drift is excessive (can only be used when stationary on ground) - uint16_t hspeed : 1; ///< 8 - true if horizontal speed is excessive (can only be used when stationary on ground) - uint16_t vspeed : 1; ///< 9 - true if vertical speed error is excessive - uint16_t spoofed: 1; ///< 10 - true if the GNSS data is spoofed - } flags; - uint16_t value; -}; - // bitmask containing filter control status union filter_control_status_u { struct { diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index b6efa80e5d..5444886870 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -94,8 +94,7 @@ void Ekf::reset() _innov_check_fail_status.value = 0; #if defined(CONFIG_EKF2_GNSS) - resetGpsDriftCheckFilters(); - _gps_checks_passed = false; + _gnss_checks.resetHard(); #endif // CONFIG_EKF2_GNSS _local_origin_alt = NAN; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index dc5a40d707..02632f0f5c 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -46,6 +46,7 @@ #include "estimator_interface.h" #if defined(CONFIG_EKF2_GNSS) +# include "aid_sources/gnss/gnss_checks.hpp" # include "yaw_estimator/EKFGSF_yaw.h" #endif // CONFIG_EKF2_GNSS @@ -376,10 +377,10 @@ public: // set minimum continuous period without GPS fail required to mark a healthy GPS status void set_min_required_gps_health_time(uint32_t time_us) { _min_gps_health_time_us = time_us; } - const gps_check_fail_status_u &gps_check_fail_status() const { return _gps_check_fail_status; } - const decltype(gps_check_fail_status_u::flags) &gps_check_fail_status_flags() const { return _gps_check_fail_status.flags; } + const GnssChecks::gps_check_fail_status_u &gps_check_fail_status() const { return _gnss_checks.getFailStatus(); } + const decltype(GnssChecks::gps_check_fail_status_u::flags) &gps_check_fail_status_flags() const { return _gnss_checks.getFailStatus().flags; } - bool gps_checks_passed() const { return _gps_checks_passed; }; + bool gps_checks_passed() const { return _gnss_checks.passed(); }; const BiasEstimator::status &getGpsHgtBiasEstimatorStatus() const { return _gps_hgt_b_est.getStatus(); } @@ -554,17 +555,6 @@ private: #if defined(CONFIG_EKF2_GNSS) bool _gps_data_ready {false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused - // variables used for the GPS quality checks - Vector3f _gps_pos_deriv_filt{}; ///< GPS NED position derivative (m/sec) - Vector2f _gps_velNE_filt{}; ///< filtered GPS North and East velocity (m/sec) - - float _gps_vel_d_filt{0.0f}; ///< GNSS filtered Down velocity (m/sec) - uint64_t _last_gps_fail_us{0}; ///< last system time in usec that the GPS failed it's checks - uint64_t _last_gps_pass_us{0}; ///< last system time in usec that the GPS passed it's checks - uint32_t _min_gps_health_time_us{10000000}; ///< GPS is marked as healthy only after this amount of time - bool _gps_checks_passed{false}; ///> true when all active GPS checks have passed - - gps_check_fail_status_u _gps_check_fail_status{}; // height sensor status bool _gps_intermittent{true}; ///< true if data into the buffer is intermittent @@ -877,34 +867,9 @@ private: void resetHorizontalPositionToGnss(estimator_aid_source2d_s &aid_src); bool shouldResetGpsFusion() const; - /* - * Return true if the GPS solution quality is adequate. - * Checks are activated using the EKF2_GPS_CHECK bitmask parameter - * Checks are adjusted using the EKF2_REQ_* parameters - */ - bool runGnssChecks(const gnssSample &gps); - - enum class GnssChecksMask : int32_t { - kNsats = (1 << 0), - kPdop = (1 << 1), - kHacc = (1 << 2), - kVacc = (1 << 3), - kSacc = (1 << 4), - kHdrift = (1 << 5), - kVdrift = (1 << 6), - kHspd = (1 << 7), - kVspd = (1 << 8), - kSpoofed = (1 << 9) - }; - - bool isGnssCheckEnabled(GnssChecksMask check); - void runOnGroundGnssChecks(const gnssSample &gnss); - void controlGnssHeightFusion(const gnssSample &gps_sample); void stopGpsHgtFusion(); - void resetGpsDriftCheckFilters(); - # if defined(CONFIG_EKF2_GNSS_YAW) void controlGnssYawFusion(const gnssSample &gps_sample); void stopGnssYawFusion(); diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 10c1832c67..18ffeef55f 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -71,6 +71,10 @@ # include "aid_sources/range_finder/sensor_range_finder.hpp" #endif // CONFIG_EKF2_RANGE_FINDER +#if defined(CONFIG_EKF2_GNSS) +# include "aid_sources/gnss/gnss_checks.hpp" +#endif // CONFIG_EKF2_GNSS + #include #include #include @@ -89,9 +93,9 @@ public: const gnssSample &get_gps_sample_delayed() const { return _gps_sample_delayed; } - float gps_horizontal_position_drift_rate_m_s() const { return _gps_horizontal_position_drift_rate_m_s; } - float gps_vertical_position_drift_rate_m_s() const { return _gps_vertical_position_drift_rate_m_s; } - float gps_filtered_horizontal_velocity_m_s() const { return _gps_filtered_horizontal_velocity_m_s; } + float gps_horizontal_position_drift_rate_m_s() const { return _gnss_checks.horizontal_position_drift_rate_m_s(); } + float gps_vertical_position_drift_rate_m_s() const { return _gnss_checks.vertical_position_drift_rate_m_s(); } + float gps_filtered_horizontal_velocity_m_s() const { return _gnss_checks.filtered_horizontal_velocity_m_s(); } #endif // CONFIG_EKF2_GNSS @@ -398,12 +402,18 @@ protected: gnssSample _gps_sample_delayed{}; - float _gps_horizontal_position_drift_rate_m_s{NAN}; // Horizontal position drift rate (m/s) - float _gps_vertical_position_drift_rate_m_s{NAN}; // Vertical position drift rate (m/s) - float _gps_filtered_horizontal_velocity_m_s{NAN}; // Filtered horizontal velocity (m/s) - - MapProjection _gnss_pos_prev{}; // Contains WGS-84 position latitude and longitude of the previous GPS message - float _gnss_alt_prev{0.0f}; // height from the previous GPS message (m) + uint32_t _min_gps_health_time_us{10000000}; ///< GPS is marked as healthy only after this amount of time + GnssChecks _gnss_checks{_params.gps_check_mask, + _params.req_nsats, + _params.req_pdop, + _params.req_hacc, + _params.req_vacc, + _params.req_sacc, + _params.req_hdrift, + _params.req_vdrift, + _params.velocity_limit, + _min_gps_health_time_us, + _control_status}; # if defined(CONFIG_EKF2_GNSS_YAW) // innovation consistency check monitoring ratios From 0e32b155f3649c333f8f548a634421150bbbf7bd Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 23 May 2025 09:59:33 +0200 Subject: [PATCH 094/130] ekf2: simplify names of scoped variables --- .../ekf2/EKF/aid_sources/gnss/gnss_checks.cpp | 133 +++++++++--------- .../ekf2/EKF/aid_sources/gnss/gnss_checks.hpp | 62 ++++---- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 2 +- 3 files changed, 96 insertions(+), 101 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp index cf216b5c65..6d41f482d5 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.cpp @@ -40,93 +40,92 @@ namespace estimator { -bool GnssChecks::runGnssChecks(const gnssSample &gnss, uint64_t time_us) +bool GnssChecks::run(const gnssSample &gnss, uint64_t time_us) { // assume failed first time through - if (_last_gps_fail_us == 0) { - _last_gps_fail_us = time_us; + if (_time_last_fail_us == 0) { + _time_last_fail_us = time_us; } bool passed = false; if (_initial_checks_passed) { if (runInitialFixChecks(gnss)) { - _last_gps_pass_us = time_us; - passed = isTimedOut(_last_gps_fail_us, time_us, math::max((uint64_t)1e6, (uint64_t)_min_gps_health_time_us / 10)); + _time_last_pass_us = time_us; + passed = isTimedOut(_time_last_fail_us, time_us, math::max((uint64_t)1e6, (uint64_t)_params.min_health_time_us / 10)); } else { - _last_gps_fail_us = time_us; + _time_last_fail_us = time_us; } } else { if (runInitialFixChecks(gnss)) { - _last_gps_pass_us = time_us; + _time_last_pass_us = time_us; - if (isTimedOut(_last_gps_fail_us, time_us, (uint64_t)_min_gps_health_time_us)) { + if (isTimedOut(_time_last_fail_us, time_us, (uint64_t)_params.min_health_time_us)) { _initial_checks_passed = true; passed = true; } } else { - _last_gps_fail_us = time_us; + _time_last_fail_us = time_us; } } - // save GPS fix for next time - _gnss_pos_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); - _gnss_alt_prev = gnss.alt; + lat_lon_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); + _alt_prev = gnss.alt; - _checks_passed = passed; + _passed = passed; return passed; } bool GnssChecks::runInitialFixChecks(const gnssSample &gnss) { // Check the fix type - _gps_check_fail_status.flags.fix = (gnss.fix_type < 3); + _check_fail_status.flags.fix = (gnss.fix_type < 3); // Check the number of satellites - _gps_check_fail_status.flags.nsats = (gnss.nsats < _params.req_nsats); + _check_fail_status.flags.nsats = (gnss.nsats < _params.req_nsats); // Check the position dilution of precision - _gps_check_fail_status.flags.pdop = (gnss.pdop > _params.req_pdop); + _check_fail_status.flags.pdop = (gnss.pdop > _params.req_pdop); // Check the reported horizontal and vertical position accuracy - _gps_check_fail_status.flags.hacc = (gnss.hacc > _params.req_hacc); - _gps_check_fail_status.flags.vacc = (gnss.vacc > _params.req_vacc); + _check_fail_status.flags.hacc = (gnss.hacc > _params.req_hacc); + _check_fail_status.flags.vacc = (gnss.vacc > _params.req_vacc); // Check the reported speed accuracy - _gps_check_fail_status.flags.sacc = (gnss.sacc > _params.req_sacc); + _check_fail_status.flags.sacc = (gnss.sacc > _params.req_sacc); - _gps_check_fail_status.flags.spoofed = gnss.spoofed; + _check_fail_status.flags.spoofed = gnss.spoofed; runOnGroundGnssChecks(gnss); // force horizontal speed failure if above the limit if (gnss.vel.xy().longerThan(_params.velocity_limit)) { - _gps_check_fail_status.flags.hspeed = true; + _check_fail_status.flags.hspeed = true; } // force vertical speed failure if above the limit if (fabsf(gnss.vel(2)) > _params.velocity_limit) { - _gps_check_fail_status.flags.vspeed = true; + _check_fail_status.flags.vspeed = true; } bool passed = true; // if any user selected checks have failed, record the fail time if ( - _gps_check_fail_status.flags.fix || - (_gps_check_fail_status.flags.nsats && isGnssCheckEnabled(GnssChecksMask::kNsats)) || - (_gps_check_fail_status.flags.pdop && isGnssCheckEnabled(GnssChecksMask::kPdop)) || - (_gps_check_fail_status.flags.hacc && isGnssCheckEnabled(GnssChecksMask::kHacc)) || - (_gps_check_fail_status.flags.vacc && isGnssCheckEnabled(GnssChecksMask::kVacc)) || - (_gps_check_fail_status.flags.sacc && isGnssCheckEnabled(GnssChecksMask::kSacc)) || - (_gps_check_fail_status.flags.hdrift && isGnssCheckEnabled(GnssChecksMask::kHdrift)) || - (_gps_check_fail_status.flags.vdrift && isGnssCheckEnabled(GnssChecksMask::kVdrift)) || - (_gps_check_fail_status.flags.hspeed && isGnssCheckEnabled(GnssChecksMask::kHspd)) || - (_gps_check_fail_status.flags.vspeed && isGnssCheckEnabled(GnssChecksMask::kVspd)) || - (_gps_check_fail_status.flags.spoofed && isGnssCheckEnabled(GnssChecksMask::kSpoofed)) + _check_fail_status.flags.fix || + (_check_fail_status.flags.nsats && isCheckEnabled(GnssChecksMask::kNsats)) || + (_check_fail_status.flags.pdop && isCheckEnabled(GnssChecksMask::kPdop)) || + (_check_fail_status.flags.hacc && isCheckEnabled(GnssChecksMask::kHacc)) || + (_check_fail_status.flags.vacc && isCheckEnabled(GnssChecksMask::kVacc)) || + (_check_fail_status.flags.sacc && isCheckEnabled(GnssChecksMask::kSacc)) || + (_check_fail_status.flags.hdrift && isCheckEnabled(GnssChecksMask::kHdrift)) || + (_check_fail_status.flags.vdrift && isCheckEnabled(GnssChecksMask::kVdrift)) || + (_check_fail_status.flags.hspeed && isCheckEnabled(GnssChecksMask::kHspd)) || + (_check_fail_status.flags.vspeed && isCheckEnabled(GnssChecksMask::kVspd)) || + (_check_fail_status.flags.spoofed && isCheckEnabled(GnssChecksMask::kSpoofed)) ) { passed = false; } @@ -139,12 +138,12 @@ void GnssChecks::runOnGroundGnssChecks(const gnssSample &gnss) if (_control_status.flags.in_air) { // These checks are always declared as passed when flying // If on ground and moving, the last result before movement commenced is kept - _gps_check_fail_status.flags.hdrift = false; - _gps_check_fail_status.flags.vdrift = false; - _gps_check_fail_status.flags.hspeed = false; - _gps_check_fail_status.flags.vspeed = false; + _check_fail_status.flags.hdrift = false; + _check_fail_status.flags.vdrift = false; + _check_fail_status.flags.hspeed = false; + _check_fail_status.flags.vspeed = false; - resetGpsDriftCheckFilters(); + resetDriftFilters(); return; } @@ -152,7 +151,7 @@ void GnssChecks::runOnGroundGnssChecks(const gnssSample &gnss) // Calculate time lapsed since last update, limit to prevent numerical errors and calculate a lowpass filter coefficient constexpr float filt_time_const = 10.0f; const float dt = math::constrain(float(int64_t(gnss.time_us) - int64_t( - _gnss_pos_prev.getProjectionReferenceTimestamp())) + lat_lon_prev.getProjectionReferenceTimestamp())) * 1e-6f, 0.001f, filt_time_const); const float filter_coef = dt / filt_time_const; @@ -160,64 +159,64 @@ void GnssChecks::runOnGroundGnssChecks(const gnssSample &gnss) float delta_pos_n = 0.0f; float delta_pos_e = 0.0f; - // calculate position movement since last GPS fix - if (_gnss_pos_prev.getProjectionReferenceTimestamp() > 0) { - _gnss_pos_prev.project(gnss.lat, gnss.lon, delta_pos_n, delta_pos_e); + // calculate position movement since last fix + if (lat_lon_prev.getProjectionReferenceTimestamp() > 0) { + lat_lon_prev.project(gnss.lat, gnss.lon, delta_pos_n, delta_pos_e); } else { // no previous position has been set - _gnss_pos_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); - _gnss_alt_prev = gnss.alt; + lat_lon_prev.initReference(gnss.lat, gnss.lon, gnss.time_us); + _alt_prev = gnss.alt; } // Calculate the horizontal and vertical drift velocity components and limit to 10x the threshold const Vector3f vel_limit(_params.req_hdrift, _params.req_hdrift, _params.req_vdrift); - Vector3f delta_pos(delta_pos_n, delta_pos_e, (_gnss_alt_prev - gnss.alt)); + Vector3f delta_pos(delta_pos_n, delta_pos_e, (_alt_prev - gnss.alt)); // Apply a low pass filter - _gps_pos_deriv_filt = delta_pos / dt * filter_coef + _gps_pos_deriv_filt * (1.0f - filter_coef); + _lat_lon_alt_deriv_filt = delta_pos / dt * filter_coef + _lat_lon_alt_deriv_filt * (1.0f - filter_coef); // Apply anti-windup to the state instead of the input to avoid generating a bias on asymmetric signals - _gps_pos_deriv_filt = matrix::constrain(_gps_pos_deriv_filt, -10.0f * vel_limit, 10.0f * vel_limit); + _lat_lon_alt_deriv_filt = matrix::constrain(_lat_lon_alt_deriv_filt, -10.0f * vel_limit, 10.0f * vel_limit); // hdrift: calculate the horizontal drift speed and fail if too high - _gps_horizontal_position_drift_rate_m_s = Vector2f(_gps_pos_deriv_filt.xy()).norm(); - _gps_check_fail_status.flags.hdrift = (_gps_horizontal_position_drift_rate_m_s > _params.req_hdrift); + _horizontal_position_drift_rate_m_s = Vector2f(_lat_lon_alt_deriv_filt.xy()).norm(); + _check_fail_status.flags.hdrift = (_horizontal_position_drift_rate_m_s > _params.req_hdrift); // vdrift: fail if the vertical drift speed is too high - _gps_vertical_position_drift_rate_m_s = fabsf(_gps_pos_deriv_filt(2)); - _gps_check_fail_status.flags.vdrift = (_gps_vertical_position_drift_rate_m_s > _params.req_vdrift); + _vertical_position_drift_rate_m_s = fabsf(_lat_lon_alt_deriv_filt(2)); + _check_fail_status.flags.vdrift = (_vertical_position_drift_rate_m_s > _params.req_vdrift); // hspeed: check the magnitude of the filtered horizontal GNSS velocity - const Vector2f gps_velNE = matrix::constrain(Vector2f(gnss.vel.xy()), - -10.0f * _params.req_hdrift, - 10.0f * _params.req_hdrift); - _gps_velNE_filt = gps_velNE * filter_coef + _gps_velNE_filt * (1.0f - filter_coef); - _gps_filtered_horizontal_velocity_m_s = _gps_velNE_filt.norm(); - _gps_check_fail_status.flags.hspeed = (_gps_filtered_horizontal_velocity_m_s > _params.req_hdrift); + const Vector2f vel_ne = matrix::constrain(Vector2f(gnss.vel.xy()), + -10.0f * _params.req_hdrift, + 10.0f * _params.req_hdrift); + _vel_ne_filt = vel_ne * filter_coef + _vel_ne_filt * (1.0f - filter_coef); + _filtered_horizontal_velocity_m_s = _vel_ne_filt.norm(); + _check_fail_status.flags.hspeed = (_filtered_horizontal_velocity_m_s > _params.req_hdrift); // vspeed: check the magnitude of the filtered vertical GNSS velocity const float gnss_vz_limit = 10.f * _params.req_vdrift; const float gnss_vz = math::constrain(gnss.vel(2), -gnss_vz_limit, gnss_vz_limit); - _gps_vel_d_filt = gnss_vz * filter_coef + _gps_vel_d_filt * (1.f - filter_coef); + _vel_d_filt = gnss_vz * filter_coef + _vel_d_filt * (1.f - filter_coef); - _gps_check_fail_status.flags.vspeed = (fabsf(_gps_vel_d_filt) > _params.req_vdrift); + _check_fail_status.flags.vspeed = (fabsf(_vel_d_filt) > _params.req_vdrift); } else { // This is the case where the vehicle is on ground and IMU movement is blocking the drift calculation - resetGpsDriftCheckFilters(); + resetDriftFilters(); } } -void GnssChecks::resetGpsDriftCheckFilters() +void GnssChecks::resetDriftFilters() { - _gps_velNE_filt.setZero(); - _gps_vel_d_filt = 0.f; + _vel_ne_filt.setZero(); + _vel_d_filt = 0.f; - _gps_pos_deriv_filt.setZero(); + _lat_lon_alt_deriv_filt.setZero(); - _gps_horizontal_position_drift_rate_m_s = NAN; - _gps_vertical_position_drift_rate_m_s = NAN; - _gps_filtered_horizontal_velocity_m_s = NAN; + _horizontal_position_drift_rate_m_s = NAN; + _vertical_position_drift_rate_m_s = NAN; + _filtered_horizontal_velocity_m_s = NAN; } }; // namespace estimator diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp index fa8ac7d2d4..af64678271 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_checks.hpp @@ -46,8 +46,7 @@ public: GnssChecks(int32_t &check_mask, int32_t &req_nsats, float &req_pdop, float &req_hacc, float &req_vacc, float &req_sacc, float &req_hdrift, float &req_vdrift, float &velocity_limit, uint32_t &min_health_time_us, filter_control_status_u &control_status): - _params{check_mask, req_nsats, req_pdop, req_hacc, req_vacc, req_sacc, req_hdrift, req_vdrift, velocity_limit}, - _min_gps_health_time_us(min_health_time_us), + _params{check_mask, req_nsats, req_pdop, req_hacc, req_vacc, req_sacc, req_hdrift, req_vdrift, velocity_limit, min_health_time_us}, _control_status(control_status) {}; @@ -76,28 +75,26 @@ public: void reset() { - _checks_passed = false; - _last_gps_pass_us = 0; - _last_gps_fail_us = 0; - resetGpsDriftCheckFilters(); + _passed = false; + _time_last_pass_us = 0; + _time_last_fail_us = 0; + resetDriftFilters(); } /* - * Return true if the GPS solution quality is adequate. - * Checks are activated using the EKF2_GPS_CHECK bitmask parameter - * Checks are adjusted using the EKF2_REQ_* parameters + * Return true if the GNSS solution quality is adequate. */ - bool runGnssChecks(const gnssSample &gps, uint64_t time_us); - bool passed() const { return _checks_passed; } + bool run(const gnssSample &gnss, uint64_t time_us); + bool passed() const { return _passed; } bool initialChecksPassed() const { return _initial_checks_passed; } - uint64_t getLastPassUs() const { return _last_gps_pass_us; } - uint64_t getLastFailUs() const { return _last_gps_fail_us; } + uint64_t getLastPassUs() const { return _time_last_pass_us; } + uint64_t getLastFailUs() const { return _time_last_fail_us; } - const gps_check_fail_status_u &getFailStatus() const { return _gps_check_fail_status; } + const gps_check_fail_status_u &getFailStatus() const { return _check_fail_status; } - float horizontal_position_drift_rate_m_s() const { return _gps_horizontal_position_drift_rate_m_s; } - float vertical_position_drift_rate_m_s() const { return _gps_vertical_position_drift_rate_m_s; } - float filtered_horizontal_velocity_m_s() const { return _gps_filtered_horizontal_velocity_m_s; } + float horizontal_position_drift_rate_m_s() const { return _horizontal_position_drift_rate_m_s; } + float vertical_position_drift_rate_m_s() const { return _vertical_position_drift_rate_m_s; } + float filtered_horizontal_velocity_m_s() const { return _filtered_horizontal_velocity_m_s; } private: enum class GnssChecksMask : int32_t { @@ -113,36 +110,35 @@ private: kSpoofed = (1 << 9) }; - bool isGnssCheckEnabled(GnssChecksMask check) { return (_params.check_mask & static_cast(check)); } + bool isCheckEnabled(GnssChecksMask check) { return (_params.check_mask & static_cast(check)); } bool runInitialFixChecks(const gnssSample &gnss); void runOnGroundGnssChecks(const gnssSample &gnss); - void resetGpsDriftCheckFilters(); + void resetDriftFilters(); bool isTimedOut(uint64_t timestamp_to_check_us, uint64_t now_us, uint64_t timeout_period) const { return (timestamp_to_check_us == 0) || (timestamp_to_check_us + timeout_period < now_us); } - gps_check_fail_status_u _gps_check_fail_status{}; + gps_check_fail_status_u _check_fail_status{}; - float _gps_horizontal_position_drift_rate_m_s{NAN}; // Horizontal position drift rate (m/s) - float _gps_vertical_position_drift_rate_m_s{NAN}; // Vertical position drift rate (m/s) - float _gps_filtered_horizontal_velocity_m_s{NAN}; // Filtered horizontal velocity (m/s) + float _horizontal_position_drift_rate_m_s{NAN}; + float _vertical_position_drift_rate_m_s{NAN}; + float _filtered_horizontal_velocity_m_s{NAN}; - MapProjection _gnss_pos_prev{}; // Contains WGS-84 position latitude and longitude of the previous GPS message - float _gnss_alt_prev{0.0f}; // height from the previous GPS message (m) + MapProjection lat_lon_prev{}; + float _alt_prev{0.0f}; - // variables used for the GPS quality checks - Vector3f _gps_pos_deriv_filt{}; - Vector2f _gps_velNE_filt{}; ///< filtered GPS North and East velocity (m/sec) + Vector3f _lat_lon_alt_deriv_filt{}; + Vector2f _vel_ne_filt{}; - float _gps_vel_d_filt{0.0f}; ///< GNSS filtered Down velocity (m/sec) - uint64_t _last_gps_fail_us{0}; - uint64_t _last_gps_pass_us{0}; + float _vel_d_filt{0.0f}; ///< GNSS filtered Down velocity (m/sec) + uint64_t _time_last_fail_us{0}; + uint64_t _time_last_pass_us{0}; bool _initial_checks_passed{false}; - bool _checks_passed{false}; + bool _passed{false}; struct Params { const int32_t &check_mask; @@ -154,10 +150,10 @@ private: const float &req_hdrift; const float &req_vdrift; const float &velocity_limit; + const uint32_t &min_health_time_us; }; const Params _params; - const uint32_t &_min_gps_health_time_us; ///< GPS is marked as healthy only after this amount of time const filter_control_status_u &_control_status; }; }; // namespace estimator diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index 2373c76481..01d15601c0 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -65,7 +65,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) const bool initial_checks_passed_prev = _gnss_checks.initialChecksPassed(); - if (_gnss_checks.runGnssChecks(gnss_sample, _time_delayed_us)) { + if (_gnss_checks.run(gnss_sample, _time_delayed_us)) { if (_gnss_checks.initialChecksPassed() && !initial_checks_passed_prev) { // First time checks are passing, latching. _information_events.flags.gps_checks_passed = true; From ae93d931d6970840fcdf52157f7ee3232a6219da Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 19 May 2025 10:37:31 -0700 Subject: [PATCH 095/130] docs: second pass at 1.16 release notes Signed-off-by: Ramon Roche --- docs/en/SUMMARY.md | 1 + docs/en/releases/1.16.md | 178 ++++++++++++++++++++++++++++++++++++++ docs/en/releases/index.md | 3 +- 3 files changed, 181 insertions(+), 1 deletion(-) create mode 100644 docs/en/releases/1.16.md diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index 7c40adb54a..aa6dcbc6d0 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -854,6 +854,7 @@ - [Licenses](contribute/licenses.md) - [Releases](releases/index.md) - [main (alpha)](releases/main.md) + - [1.16 (release candidate)](releases/1.16.md) - [1.15 (stable)](releases/1.15.md) - [1.14](releases/1.14.md) - [1.13](releases/1.13.md) diff --git a/docs/en/releases/1.16.md b/docs/en/releases/1.16.md new file mode 100644 index 0000000000..274abcfff0 --- /dev/null +++ b/docs/en/releases/1.16.md @@ -0,0 +1,178 @@ +# PX4-Autopilot Main Release Notes + + + +This document covers all changes in PX4 `v1.16.0` since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)). + +::: warning +These notes include only changes merged in 2023 and later—no commits from before 2023 are listed. +::: + +## Read Before Upgrading + +Please continue reading for [upgrade instructions](#upgrade-guide). + +## Major Changes + +- **Rover support rework** + - New dedicated firmware build for rovers (airframe IDs 50000–52000) + - Separate modules for Ackermann, differential and mecanum rovers, each with manual, acro, stabilized, position and auto modes + - Shared pure-pursuit guidance library for all rover modules + - Legacy rover position control module deprecated in favor of the new modules + +## Upgrade Guide + +- [PX4-Autopilot#24648](https://github.com/PX4/PX4-Autopilot/pull/24648): Added setting default for EKF2_EV_CTRL to 15 for VOXL 2 boards +- [PX4-Autopilot#22517](https://github.com/PX4/PX4-Autopilot/pull/22517): Change default ethernet IP +- [PX4-Autopilot#24602](https://github.com/PX4/PX4-Autopilot/pull/24602): remove serial port default from sf45 module + +## Other changes + +### Hardware Support +- **[New Hardware]** [PX4-Autopilot#23830](https://github.com/PX4/PX4-Autopilot/pull/23830): Boards: ARK FPV FC +- **[New Hardware]** [PX4-Autopilot#23414](https://github.com/PX4/PX4-Autopilot/pull/23414): board: add cuav 7-nano +- **[New Hardware]** [PX4-Autopilot#24769](https://github.com/PX4/PX4-Autopilot/pull/24769): add new board corvon743v1 +- **[New Hardware]** [PX4-Autopilot#24018](https://github.com/PX4/PX4-Autopilot/pull/24018): boards: bluerobotics: navigator: Add initial support +- **[New Hardware]** [PX4-Autopilot#24147](https://github.com/PX4/PX4-Autopilot/pull/24147): boards: add new board micoair743-v2 +- **[New Hardware]** [PX4-Autopilot#23218](https://github.com/PX4/PX4-Autopilot/pull/23218): boards: add new board micoair h743 +- **[New Hardware]** [PX4-Autopilot#24512](https://github.com/PX4/PX4-Autopilot/pull/24512): boards: Add FMUv6s target +- **[New Hardware]** [PX4-Autopilot#23927](https://github.com/PX4/PX4-Autopilot/pull/23927): manifest: Add Skynode S baseboard +- **[New Hardware]** [PX4-Autopilot#23257](https://github.com/PX4/PX4-Autopilot/pull/23257): Add Tropic VMU board support (Baseboard for Teensy 4.1) +- **[New Hardware]** [PX4-Autopilot#23697](https://github.com/PX4/PX4-Autopilot/pull/23697): boards: add new board X-MAV AP-H743v2 +- **[New Hardware]** [PX4-Autopilot#23551](https://github.com/PX4/PX4-Autopilot/pull/23551): 3DR boards: Support for 3DR Control Zero H7 OEM Rev G +- **[New Hardware]** [PX4-Autopilot#23623](https://github.com/PX4/PX4-Autopilot/pull/23623): new board support ZeroOne x6 + + +### Common +- [PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936): Optical flow: add scale factor parameter +- [PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813): Reintroduce optional parameter versioning mechanism for airframe maintainers + +- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)). + - [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage. + - Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number). +- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed. + The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)). +- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. + This makes log decryption much easier, as there is no need to download or identify a separate key file. + ([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)). +- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter. + Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. + This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. + ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). +- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) +- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available. + This typically reduces false warnings due to magnetometer inconsistencies. + ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). + +### Control +- [PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863): [Sponsored by ARK] Bidirectional DShot +- [PX4-Autopilot#24196](https://github.com/PX4/PX4-Autopilot/pull/24196): Make control allocation and actuator effectiveness a non-module-specific library +- [PX4-Autopilot#24221](https://github.com/PX4/PX4-Autopilot/pull/24221): Spacecraft Build and Bare Control Allocator + +- Configurable multicopter orbit-mode yaw via `MC_ORBIT_YAW_MOD` ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) +- Collision prevention now works in manual (acceleration-based) flight mode (`MPC_POS_MODE`) ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507)) + + +### Estimation +- [PX4-Autopilot#23854](https://github.com/PX4/PX4-Autopilot/pull/23854): EKF2: ellipsoidal earth navigation +- [PX4-Autopilot#23263](https://github.com/PX4/PX4-Autopilot/pull/23263): EKF2: Terrain state +- [PX4-Autopilot#23185](https://github.com/PX4/PX4-Autopilot/pull/23185): ekf2: add mag type init +- [PX4-Autopilot#23436](https://github.com/PX4/PX4-Autopilot/pull/23436): ekf2: Optical flow enabled by default + +- Position-loss failsafe delay removed; triggers 1 s after loss (see Common) + +### Sensors +- [PX4-Autopilot#23656](https://github.com/PX4/PX4-Autopilot/pull/23656): Implemented AUAV absolute/differential pressure sensor support +- [PX4-Autopilot#23639](https://github.com/PX4/PX4-Autopilot/pull/23639): Implemented temperature sensor support for INA228 / INA238 +- [PX4-Autopilot#22744](https://github.com/PX4/PX4-Autopilot/pull/22744): Add Ublox ZED-F9P-15B +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Mag cal: automatically disable internal mags if external ones are available +- [PX4-Autopilot#23064](https://github.com/PX4/PX4-Autopilot/pull/23064): BMP581: Add Bosch BMP581 barometer +- [PX4-Autopilot#22914](https://github.com/PX4/PX4-Autopilot/pull/22914): Murata SCH16T IMU driver +- [PX4-Autopilot#23023](https://github.com/PX4/PX4-Autopilot/pull/23023): ST IIS2MDC Magnetometer driver +- [PX4-Autopilot#24121](https://github.com/PX4/PX4-Autopilot/pull/24121): Include distance sensor in dds topics +- [PX4-Autopilot#23925](https://github.com/PX4/PX4-Autopilot/pull/23925): drivers: magnetometer: mmc5983ma: Add SPI support +- [PX4-Autopilot#23909](https://github.com/PX4/PX4-Autopilot/pull/23909): drivers/magnetometer/ak09916: Add support to AK09915 +- [PX4-Autopilot#23362](https://github.com/PX4/PX4-Autopilot/pull/23362): Add Bosch BMM350 magnetometer + +- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Compass calibration now disables internal compass when external unit present, reducing false warnings + +### Simulation + +- **SIH**: + - The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. + ([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)). + - SIH now supports the standard VTOL airframe + ([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)). +- **Gazebo**: + - Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. + The default installer scripts (used for CI) and documentation have been updated. + This is required because Garden end-of-life is Nov 2024. + ([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603)) + - New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)). + - New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)). + - New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)). + - New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)). + - New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)). + - New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)). + - New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)). + - [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783)) + - [PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471): Gazebo: Moving platform + +### uXRCE-DDS / ROS2 +- **[Feature]** [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically +- [PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582): dds_topics: add vtol_vehicle_status +- [PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583): dds_topics: add home_position + +### MAVLink + +- TBD + +### Multi-Rotor +- [PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173): [Multirotor] add yaw torque low pass filter +- [PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943): Add gz model for quadtailsitter + +- [PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358): Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) +- [PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507): Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). + +### VTOL + +- TBD + +### Fixed-wing +- [PX4-Autopilot#24167](https://github.com/PX4/PX4-Autopilot/pull/24167): Fixedwing: fix wheel controller +- [PX4-Autopilot#23520](https://github.com/PX4/PX4-Autopilot/pull/23520): FixedWing: allow position control without valid global position + +- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460) + +### Rover + +This release contains a major rework for the rover support in PX4: + +- Complete restructure of the [rover related documentation](../frames_rover/index.md). +- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build). +- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md): + - The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes). +- New module dedicated to [differential rovers](../frames_rover/differential.md): + - The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes). +- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md): + - The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes). +- Added rover-specific firmware build (`50000–52000`) for Ackermann, differential and mecanum rovers +- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)). + This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover): + - Generic Differential Rover `50000`. + - Generic Ackermann Rover `51000`. + - Axial SCX10 2 Trail Honcho `51001`. + - Generic Mecanum Rover `52000`. +- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules. +- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)). +- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. + +### Infrastructure +- [PX4-Autopilot#24011](https://github.com/PX4/PX4-Autopilot/pull/24011): standard_modes: add vehicle-type specific standard modes +- [PX4-Autopilot#24020](https://github.com/PX4/PX4-Autopilot/pull/24020): ci: build all upload to releases +- [PX4-Autopilot#24002](https://github.com/PX4/PX4-Autopilot/pull/24002): ci: px4-dev container +- [PX4-Autopilot#23937](https://github.com/PX4/PX4-Autopilot/pull/23937): ci: workflow for ubuntu 24 +- [PX4-Autopilot#23869](https://github.com/PX4/PX4-Autopilot/pull/23869): ci: add test for Ubuntu 22.04 +- [PX4-Autopilot#23574](https://github.com/PX4/PX4-Autopilot/pull/23574): ci: try runs-on Dronecode Infra +- [PX4-Autopilot#23550](https://github.com/PX4/PX4-Autopilot/pull/23550): ci: replace build workflows diff --git a/docs/en/releases/index.md b/docs/en/releases/index.md index 4fedd56bbd..7c5aa295c5 100644 --- a/docs/en/releases/index.md +++ b/docs/en/releases/index.md @@ -2,7 +2,8 @@ A list of PX4 release notes, they contain a list of the changes that went into each release, explaining the included features, bug fixes, deprecations and updates in detail. -- [main](../releases/main.md) (changes since v1.15) +- [main](../releases/main.md) (changes since v1.16) +- [v1.16](../releases/1.16.md) - [v1.15](../releases/1.15.md) - [v1.14](../releases/1.14.md) - [v1.13](../releases/1.13.md) From 265ab8541492a2627c9c9f4969569f6f37e907c4 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 4 Jun 2025 11:27:03 +1000 Subject: [PATCH 096/130] prettier --- docs/en/releases/1.16.md | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/docs/en/releases/1.16.md b/docs/en/releases/1.16.md index 274abcfff0..936573ee9d 100644 --- a/docs/en/releases/1.16.md +++ b/docs/en/releases/1.16.md @@ -1,8 +1,8 @@ -# PX4-Autopilot Main Release Notes +# PX4-Autopilot v1.16.0 Release Notes -This document covers all changes in PX4 `v1.16.0` since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)). +This document covers all changes in PX4 v1.16.0 since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)). ::: warning These notes include only changes merged in 2023 and later—no commits from before 2023 are listed. @@ -29,6 +29,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ## Other changes ### Hardware Support + - **[New Hardware]** [PX4-Autopilot#23830](https://github.com/PX4/PX4-Autopilot/pull/23830): Boards: ARK FPV FC - **[New Hardware]** [PX4-Autopilot#23414](https://github.com/PX4/PX4-Autopilot/pull/23414): board: add cuav 7-nano - **[New Hardware]** [PX4-Autopilot#24769](https://github.com/PX4/PX4-Autopilot/pull/24769): add new board corvon743v1 @@ -42,8 +43,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). - **[New Hardware]** [PX4-Autopilot#23551](https://github.com/PX4/PX4-Autopilot/pull/23551): 3DR boards: Support for 3DR Control Zero H7 OEM Rev G - **[New Hardware]** [PX4-Autopilot#23623](https://github.com/PX4/PX4-Autopilot/pull/23623): new board support ZeroOne x6 - ### Common + - [PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936): Optical flow: add scale factor parameter - [PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813): Reintroduce optional parameter versioning mechanism for airframe maintainers @@ -65,6 +66,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)). ### Control + - [PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863): [Sponsored by ARK] Bidirectional DShot - [PX4-Autopilot#24196](https://github.com/PX4/PX4-Autopilot/pull/24196): Make control allocation and actuator effectiveness a non-module-specific library - [PX4-Autopilot#24221](https://github.com/PX4/PX4-Autopilot/pull/24221): Spacecraft Build and Bare Control Allocator @@ -72,8 +74,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). - Configurable multicopter orbit-mode yaw via `MC_ORBIT_YAW_MOD` ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358)) - Collision prevention now works in manual (acceleration-based) flight mode (`MPC_POS_MODE`) ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507)) - ### Estimation + - [PX4-Autopilot#23854](https://github.com/PX4/PX4-Autopilot/pull/23854): EKF2: ellipsoidal earth navigation - [PX4-Autopilot#23263](https://github.com/PX4/PX4-Autopilot/pull/23263): EKF2: Terrain state - [PX4-Autopilot#23185](https://github.com/PX4/PX4-Autopilot/pull/23185): ekf2: add mag type init @@ -82,6 +84,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). - Position-loss failsafe delay removed; triggers 1 s after loss (see Common) ### Sensors + - [PX4-Autopilot#23656](https://github.com/PX4/PX4-Autopilot/pull/23656): Implemented AUAV absolute/differential pressure sensor support - [PX4-Autopilot#23639](https://github.com/PX4/PX4-Autopilot/pull/23639): Implemented temperature sensor support for INA228 / INA238 - [PX4-Autopilot#22744](https://github.com/PX4/PX4-Autopilot/pull/22744): Add Ublox ZED-F9P-15B @@ -120,6 +123,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). - [PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471): Gazebo: Moving platform ### uXRCE-DDS / ROS2 + - **[Feature]** [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically - [PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582): dds_topics: add vtol_vehicle_status - [PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583): dds_topics: add home_position @@ -129,6 +133,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). - TBD ### Multi-Rotor + - [PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173): [Multirotor] add yaw torque low pass filter - [PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943): Add gz model for quadtailsitter @@ -140,6 +145,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). - TBD ### Fixed-wing + - [PX4-Autopilot#24167](https://github.com/PX4/PX4-Autopilot/pull/24167): Fixedwing: fix wheel controller - [PX4-Autopilot#23520](https://github.com/PX4/PX4-Autopilot/pull/23520): FixedWing: allow position control without valid global position @@ -169,6 +175,7 @@ This release contains a major rework for the rover support in PX4: - Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules. ### Infrastructure + - [PX4-Autopilot#24011](https://github.com/PX4/PX4-Autopilot/pull/24011): standard_modes: add vehicle-type specific standard modes - [PX4-Autopilot#24020](https://github.com/PX4/PX4-Autopilot/pull/24020): ci: build all upload to releases - [PX4-Autopilot#24002](https://github.com/PX4/PX4-Autopilot/pull/24002): ci: px4-dev container From ee49469cb6238cfb3098832e26293fd616511f7b Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 4 Jun 2025 12:02:00 +1000 Subject: [PATCH 097/130] Remove content of main --- docs/en/releases/1.16.md | 19 ++++++++--- docs/en/releases/main.md | 73 ++++++---------------------------------- 2 files changed, 25 insertions(+), 67 deletions(-) diff --git a/docs/en/releases/1.16.md b/docs/en/releases/1.16.md index 936573ee9d..9e293b6e62 100644 --- a/docs/en/releases/1.16.md +++ b/docs/en/releases/1.16.md @@ -1,11 +1,22 @@ # PX4-Autopilot v1.16.0 Release Notes - + + + + +